openrave.org

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
OpenRAVE::IkSolverBase Class Referenceabstract

[interface] Base class for all Inverse Kinematic solvers. If not specified, method is not multi-thread safe. See Inverse Kinematics Solver Concepts. More...

#include <iksolver.h>

Inheritance diagram for OpenRAVE::IkSolverBase:
Inheritance graph
[legend]
Collaboration diagram for OpenRAVE::IkSolverBase:
Collaboration graph
[legend]

Public Types

typedef boost::function
< IkReturn(std::vector< dReal >
&, RobotBase::ManipulatorConstPtr,
const IkParameterization &)> 
IkFilterCallbackFn
 
- Public Types inherited from OpenRAVE::InterfaceBase
typedef std::map< std::string,
XMLReadablePtr,
CaseInsensitiveCompare
READERSMAP
 

Public Member Functions

 IkSolverBase (EnvironmentBasePtr penv)
 
virtual ~IkSolverBase ()
 
virtual bool Init (RobotBase::ManipulatorConstPtr pmanip)=0
 
virtual RobotBase::ManipulatorPtr GetManipulator () const =0
 
virtual UserDataPtr RegisterCustomFilter (int priority, const IkFilterCallbackFn &filterfn)
 Sets an ik solution filter that is called for every ik solution.
 
virtual void SetCustomFilter (const IkFilterCallbackFn &filterfn) RAVE_DEPRECATED
 
virtual int GetNumFreeParameters () const =0
 Number of free parameters defining the null solution space.
 
virtual bool GetFreeParameters (std::vector< dReal > &vFreeParameters) const =0
 gets the free parameters from the current robot configuration
 
virtual bool Solve (const IkParameterization &param, const std::vector< dReal > &q0, int filteroptions, boost::shared_ptr< std::vector< dReal > > solution=boost::shared_ptr< std::vector< dReal > >())=0
 Return a joint configuration for the given end effector transform.
 
virtual bool Solve (const IkParameterization &param, const std::vector< dReal > &q0, int filteroptions, IkReturnPtr ikreturn)
 Return a joint configuration for the given end effector transform.
 
virtual bool SolveAll (const IkParameterization &param, int filteroptions, std::vector< std::vector< dReal > > &solutions)=0
 Return all joint configurations for the given end effector transform.
 
virtual bool Solve (const IkParameterization &param, int filteroptions, std::vector< std::vector< dReal > > &solutions) RAVE_DEPRECATED
 
virtual bool SolveAll (const IkParameterization &param, int filteroptions, std::vector< IkReturnPtr > &ikreturns)
 Return all joint configurations for the given end effector transform.
 
virtual bool Solve (const IkParameterization &param, const std::vector< dReal > &q0, const std::vector< dReal > &vFreeParameters, int filteroptions, boost::shared_ptr< std::vector< dReal > > solution=boost::shared_ptr< std::vector< dReal > >())=0
 
virtual bool Solve (const IkParameterization &param, const std::vector< dReal > &q0, const std::vector< dReal > &vFreeParameters, int filteroptions, IkReturnPtr ikreturn)
 
virtual bool SolveAll (const IkParameterization &param, const std::vector< dReal > &vFreeParameters, int filteroptions, std::vector< std::vector< dReal > > &solutions)=0
 Return all joint configurations for the given end effector transform.
 
virtual bool Solve (const IkParameterization &param, const std::vector< dReal > &vFreeParameters, int filteroptions, std::vector< std::vector< dReal > > &solutions) RAVE_DEPRECATED
 
virtual bool SolveAll (const IkParameterization &param, const std::vector< dReal > &vFreeParameters, int filteroptions, std::vector< IkReturnPtr > &ikreturns)
 Return all joint configurations for the given end effector transform.
 
virtual bool Supports (IkParameterizationType iktype) const OPENRAVE_DUMMY_IMPLEMENTATION
 returns true if the solver supports a particular ik parameterization as input.
 
- Public Member Functions inherited from OpenRAVE::InterfaceBase
 InterfaceBase (InterfaceType type, EnvironmentBasePtr penv)
 
virtual ~InterfaceBase ()
 
InterfaceType GetInterfaceType () const
 
const std::string & GetXMLId () const
 
const std::string & GetPluginName () const
 
EnvironmentBasePtr GetEnv () const
 
const READERSMAPGetReadableInterfaces () const
 Returns the raw map reference, this is not multithread safe and the GetInterfaceMutex should be locked before using.
 
virtual XMLReadablePtr GetReadableInterface (const std::string &xmltag) const
 Returns the readable interface. [multi-thread safe]
 
virtual XMLReadablePtr SetReadableInterface (const std::string &xmltag, XMLReadablePtr readable)
 Set a new readable interface and return the previously set interface if it exists. [multi-thread safe]
 
virtual const std::string & GetDescription () const
 Documentation of the interface in reStructuredText format. See Documenting Interfaces. [multi-thread safe]
 
virtual void SetDescription (const std::string &description)
 sets a description [multi-thread safe]
 
virtual void SetUserData (const std::string &key, UserDataPtr data) const
 set user data for a specific key. [multi-thread safe]
 
virtual UserDataPtr GetUserData (const std::string &key=std::string()) const
 return the user custom data [multi-thread safe]
 
virtual bool RemoveUserData (const std::string &key) const
 removes a user data pointer. if user data pointer does not exist, then return 0, otherwise 1. [multi-thread safe]
 
virtual void SetUserData (UserDataPtr data) RAVE_DEPRECATED
 
virtual const std::string & GetURI () const
 the URI used to load the interface (sometimes this is not possible if the definition lies inside an environment file). [multi-thread safe]
 
virtual const std::string & GetXMLFilename () const
 
virtual void Clone (InterfaceBaseConstPtr preference, int cloningoptions)
 Clone the contents of an interface to the current interface.
 
virtual bool SendCommand (std::ostream &os, std::istream &is)
 Used to send special commands to the interface and receive output.
 
virtual void Serialize (BaseXMLWriterPtr writer, int options=0) const
 serializes the interface
 

Static Public Member Functions

static InterfaceType GetInterfaceTypeStatic ()
 return the static interface type this class points to (used for safe casting)
 

Protected Member Functions

IkSolverBasePtr shared_iksolver ()
 
IkSolverBaseConstPtr shared_iksolver_const () const
 
virtual IkReturnAction _CallFilters (std::vector< dReal > &solution, RobotBase::ManipulatorPtr manipulator, const IkParameterization &param, IkReturnPtr ikreturn=IkReturnPtr())
 calls the registered filters in their priority order and returns the value of the last called filter.
 
- Protected Member Functions inherited from OpenRAVE::InterfaceBase
virtual void RegisterCommand (const std::string &cmdname, InterfaceCommandFn fncmd, const std::string &strhelp)
 Registers a command and its help string. [multi-thread safe]
 
virtual void UnregisterCommand (const std::string &cmdname)
 Unregisters the command. [multi-thread safe]
 
virtual boost::shared_mutex & GetInterfaceMutex () const
 

Additional Inherited Members

- Protected Types inherited from OpenRAVE::InterfaceBase
typedef boost::function< bool(std::ostream
&, std::istream &)> 
InterfaceCommandFn
 The function to be executed for every command.
 
- Protected Attributes inherited from OpenRAVE::InterfaceBase
std::string __description
 

Detailed Description

[interface] Base class for all Inverse Kinematic solvers. If not specified, method is not multi-thread safe. See Inverse Kinematics Solver Concepts.

Definition at line 94 of file iksolver.h.

Member Typedef Documentation

Inverse kinematics filter callback function.

The filter is of the form return = filterfn(solution, manipulator, param). The solution is guaranteed to be set on the robot's joint values before this function is called. The active dof values of the robot will be set to the manipulator's arms. If the filter internally modifies the robot state and it returns IKRA_Success, the filter has to restore the original robot dof values and active dofs before it returns. If the filter happens to modify solution, the the robot state has to be set to the new solution.

Parameters
solutionThe current solution of the manipulator. Can be modified by this function, but note that it will not go through previous checks again.
manipulatorThe current manipulator that the ik is being solved for.
paramThe paramterization that IK was called with. This is in the manipulator base link's coordinate system (which is not necessarily the world coordinate system).
Returns
IkReturn outputs the action to take for the current ik solution and any custom parameters the filter should pass to the user.

Definition at line 109 of file iksolver.h.

Constructor & Destructor Documentation

OpenRAVE::IkSolverBase::IkSolverBase ( EnvironmentBasePtr  penv)
inline

Definition at line 111 of file iksolver.h.

virtual OpenRAVE::IkSolverBase::~IkSolverBase ( )
inlinevirtual

Definition at line 113 of file iksolver.h.

Member Function Documentation

IkReturnAction OpenRAVE::IkSolverBase::_CallFilters ( std::vector< dReal > &  solution,
RobotBase::ManipulatorPtr  manipulator,
const IkParameterization param,
IkReturnPtr  ikreturn = IkReturnPtr() 
)
protectedvirtual

calls the registered filters in their priority order and returns the value of the last called filter.

The parameters are the same as IkFilterCallbackFn, except the IkReturn is an optional input parameter and the return value is just the IkReturnAction. For users that do not request the filter output, this allows the computation

Definition at line 160 of file iksolver.cpp.

virtual bool OpenRAVE::IkSolverBase::GetFreeParameters ( std::vector< dReal > &  vFreeParameters) const
pure virtual

gets the free parameters from the current robot configuration

Parameters
[out]vFreeParametersis filled with GetNumFreeParameters() parameters in [0,1] range
Returns
true if succeeded
static InterfaceType OpenRAVE::IkSolverBase::GetInterfaceTypeStatic ( )
inlinestatic

return the static interface type this class points to (used for safe casting)

Definition at line 117 of file iksolver.h.

virtual RobotBase::ManipulatorPtr OpenRAVE::IkSolverBase::GetManipulator ( ) const
pure virtual
virtual int OpenRAVE::IkSolverBase::GetNumFreeParameters ( ) const
pure virtual

Number of free parameters defining the null solution space.

Each parameter is always in the range of [0,1].

virtual bool OpenRAVE::IkSolverBase::Init ( RobotBase::ManipulatorConstPtr  pmanip)
pure virtual

brief Sets the IkSolverBase attached to a specific robot and sets IkSolverBase specific options.

For example, some ik solvers might have different ways of computing optimal solutions.

Parameters
pmanipThe manipulator the IK solver is attached to
UserDataPtr OpenRAVE::IkSolverBase::RegisterCustomFilter ( int  priority,
const IkFilterCallbackFn filterfn 
)
virtual

Sets an ik solution filter that is called for every ik solution.

Multiple filters can be set at once, each filter will be called according to its priority; higher values get called first. The default implementation of IkSolverBase manages the filters internally. Users implementing their own IkSolverBase should call _CallFilters to run the internally managed filters.

Parameters
priority- The priority of the filter that controls the order in which filters get called. Higher priority filters get called first. If not certain what to set, use 0.
filterfn- an optional filter function to be called, see IkFilterCallbackFn.
Returns
a managed handle to the filter. If this handle is released, then the fitler will be removed. Release operation is [multi-thread safe].

Definition at line 146 of file iksolver.cpp.

virtual void OpenRAVE::IkSolverBase::SetCustomFilter ( const IkFilterCallbackFn filterfn)
inlinevirtual
Deprecated:
(11/09/21)

Definition at line 139 of file iksolver.h.

IkSolverBasePtr OpenRAVE::IkSolverBase::shared_iksolver ( )
inlineprotected

Definition at line 264 of file iksolver.h.

IkSolverBaseConstPtr OpenRAVE::IkSolverBase::shared_iksolver_const ( ) const
inlineprotected

Definition at line 267 of file iksolver.h.

virtual bool OpenRAVE::IkSolverBase::Solve ( const IkParameterization param,
const std::vector< dReal > &  q0,
int  filteroptions,
boost::shared_ptr< std::vector< dReal > >  solution = boost::shared_ptr< std::vector< dReal > >() 
)
pure virtual

Return a joint configuration for the given end effector transform.

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]q0Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is NULL, returns the first solution found
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]solution[optional] Holds the IK solution
Returns
true if solution is found
bool OpenRAVE::IkSolverBase::Solve ( const IkParameterization param,
const std::vector< dReal > &  q0,
int  filteroptions,
IkReturnPtr  ikreturn 
)
virtual

Return a joint configuration for the given end effector transform.

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]q0Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is NULL, returns the first solution found
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]ikreturnHolds all the ik output data (including ik solutions) from the many processes involved in solving ik.
Returns
true if solution is found

Definition at line 84 of file iksolver.cpp.

virtual bool OpenRAVE::IkSolverBase::Solve ( const IkParameterization param,
int  filteroptions,
std::vector< std::vector< dReal > > &  solutions 
)
inlinevirtual
Deprecated:
(12/05/01)

Definition at line 193 of file iksolver.h.

virtual bool OpenRAVE::IkSolverBase::Solve ( const IkParameterization param,
const std::vector< dReal > &  q0,
const std::vector< dReal > &  vFreeParameters,
int  filteroptions,
boost::shared_ptr< std::vector< dReal > >  solution = boost::shared_ptr< std::vector< dReal > >() 
)
pure virtual

Return a joint configuration for the given end effector transform.

Can specify the free parameters in [0,1] range. If NULL, the regular equivalent Solve is called

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]q0Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is empty, returns the first solution found
[in]vFreeParametersThe free parameters of the null space of the IK solutions. Always in range of [0,1]
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]solution[optional] Holds the IK solution, must be of size RobotBase::Manipulator::_vecarmjoints
Returns
true if solution is found
bool OpenRAVE::IkSolverBase::Solve ( const IkParameterization param,
const std::vector< dReal > &  q0,
const std::vector< dReal > &  vFreeParameters,
int  filteroptions,
IkReturnPtr  ikreturn 
)
virtual

Return a joint configuration for the given end effector transform.

Can specify the free parameters in [0,1] range. If NULL, the regular equivalent Solve is called

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]q0Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is empty, returns the first solution found
[in]vFreeParametersThe free parameters of the null space of the IK solutions. Always in range of [0,1]
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]ikreturnHolds all the ik output data (including ik solutions) from the many processes involved in solving ik.
Returns
true if solution is found

Definition at line 115 of file iksolver.cpp.

virtual bool OpenRAVE::IkSolverBase::Solve ( const IkParameterization param,
const std::vector< dReal > &  vFreeParameters,
int  filteroptions,
std::vector< std::vector< dReal > > &  solutions 
)
inlinevirtual
Deprecated:
(12/05/01)

Definition at line 244 of file iksolver.h.

virtual bool OpenRAVE::IkSolverBase::SolveAll ( const IkParameterization param,
int  filteroptions,
std::vector< std::vector< dReal > > &  solutions 
)
pure virtual

Return all joint configurations for the given end effector transform.

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]solutionsAll solutions within a reasonable discretization level of the free parameters.
Returns
true if at least one solution is found
bool OpenRAVE::IkSolverBase::SolveAll ( const IkParameterization param,
int  filteroptions,
std::vector< IkReturnPtr > &  ikreturns 
)
virtual

Return all joint configurations for the given end effector transform.

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]ikreturnsHolds all the ik output data (including ik solutions) from the many processes involved in solving ik.
Returns
true if at least one solution is found

Definition at line 99 of file iksolver.cpp.

virtual bool OpenRAVE::IkSolverBase::SolveAll ( const IkParameterization param,
const std::vector< dReal > &  vFreeParameters,
int  filteroptions,
std::vector< std::vector< dReal > > &  solutions 
)
pure virtual

Return all joint configurations for the given end effector transform.

Can specify the free parameters in [0,1] range. If NULL, the regular equivalent Solve is called

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]vFreeParametersThe free parameters of the null space of the IK solutions. Always in range of [0,1]
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]solutionsAll solutions within a reasonable discretization level of the free parameters.
Returns
true at least one solution is found
bool OpenRAVE::IkSolverBase::SolveAll ( const IkParameterization param,
const std::vector< dReal > &  vFreeParameters,
int  filteroptions,
std::vector< IkReturnPtr > &  ikreturns 
)
virtual

Return all joint configurations for the given end effector transform.

Can specify the free parameters in [0,1] range. If NULL, the regular equivalent Solve is called

Parameters
[in]paramthe pose the end effector has to achieve. Note that the end effector pose takes into account the grasp coordinate frame for the RobotBase::Manipulator
[in]vFreeParametersThe free parameters of the null space of the IK solutions. Always in range of [0,1]
[in]filteroptionsA bitmask of IkFilterOptions values controlling what is checked for each ik solution.
[out]ikreturnsHolds all the ik output data (including ik solutions) from the many processes involved in solving ik.
Returns
true at least one solution is found

Definition at line 130 of file iksolver.cpp.

virtual bool OpenRAVE::IkSolverBase::Supports ( IkParameterizationType  iktype) const
virtual

returns true if the solver supports a particular ik parameterization as input.


The documentation for this class was generated from the following files: