[interface] Base class for all Inverse Kinematic solvers. If not specified, method is not multi-thread safe. See Inverse Kinematics Solver Concepts. [詳細]
#include <iksolver.h>
Public 型 | |
typedef boost::function < IkReturn(std::vector< dReal > &, RobotBase::ManipulatorConstPtr, const IkParameterization &)> | IkFilterCallbackFn |
![]() | |
typedef std::map< std::string, XMLReadablePtr, CaseInsensitiveCompare > | READERSMAP |
Public メソッド | |
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 ¶m, 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 ¶m, const std::vector< dReal > &q0, int filteroptions, IkReturnPtr ikreturn) |
Return a joint configuration for the given end effector transform. | |
virtual bool | SolveAll (const IkParameterization ¶m, int filteroptions, std::vector< std::vector< dReal > > &solutions)=0 |
Return all joint configurations for the given end effector transform. | |
virtual bool | Solve (const IkParameterization ¶m, int filteroptions, std::vector< std::vector< dReal > > &solutions) RAVE_DEPRECATED |
virtual bool | SolveAll (const IkParameterization ¶m, int filteroptions, std::vector< IkReturnPtr > &ikreturns) |
Return all joint configurations for the given end effector transform. | |
virtual bool | Solve (const IkParameterization ¶m, 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 ¶m, const std::vector< dReal > &q0, const std::vector< dReal > &vFreeParameters, int filteroptions, IkReturnPtr ikreturn) |
virtual bool | SolveAll (const IkParameterization ¶m, 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 ¶m, const std::vector< dReal > &vFreeParameters, int filteroptions, std::vector< std::vector< dReal > > &solutions) RAVE_DEPRECATED |
virtual bool | SolveAll (const IkParameterization ¶m, 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. | |
![]() | |
InterfaceBase (InterfaceType type, EnvironmentBasePtr penv) | |
virtual | ~InterfaceBase () |
InterfaceType | GetInterfaceType () const |
const std::string & | GetXMLId () const |
const std::string & | GetPluginName () const |
EnvironmentBasePtr | GetEnv () const |
const READERSMAP & | GetReadableInterfaces () 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 メソッド | |
static InterfaceType | GetInterfaceTypeStatic () |
return the static interface type this class points to (used for safe casting) | |
Protected メソッド | |
IkSolverBasePtr | shared_iksolver () |
IkSolverBaseConstPtr | shared_iksolver_const () const |
virtual IkReturnAction | _CallFilters (std::vector< dReal > &solution, RobotBase::ManipulatorPtr manipulator, const IkParameterization ¶m, IkReturnPtr ikreturn=IkReturnPtr()) |
calls the registered filters in their priority order and returns the value of the last called filter. | |
![]() | |
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 | |
![]() | |
typedef boost::function< bool(std::ostream &, std::istream &)> | InterfaceCommandFn |
The function to be executed for every command. | |
![]() | |
std::string | __description |
[interface] Base class for all Inverse Kinematic solvers. If not specified, method is not multi-thread safe. See Inverse Kinematics Solver Concepts.
iksolver.h の 94 行で定義されています。
typedef boost::function<IkReturn(std::vector<dReal>&, RobotBase::ManipulatorConstPtr, const IkParameterization&)> OpenRAVE::IkSolverBase::IkFilterCallbackFn |
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.
solution | The current solution of the manipulator. Can be modified by this function, but note that it will not go through previous checks again. |
manipulator | The current manipulator that the ik is being solved for. |
param | The paramterization that IK was called with. This is in the manipulator base link's coordinate system (which is not necessarily the world coordinate system). |
iksolver.h の 109 行で定義されています。
|
inline |
iksolver.h の 111 行で定義されています。
|
inlinevirtual |
iksolver.h の 113 行で定義されています。
|
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
iksolver.cpp の 160 行で定義されています。
|
pure virtual |
gets the free parameters from the current robot configuration
[out] | vFreeParameters | is filled with GetNumFreeParameters() parameters in [0,1] range |
|
inlinestatic |
return the static interface type this class points to (used for safe casting)
iksolver.h の 117 行で定義されています。
|
pure virtual |
|
pure virtual |
Number of free parameters defining the null solution space.
Each parameter is always in the range of [0,1].
|
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.
pmanip | The manipulator the IK solver is attached to |
|
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.
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. |
iksolver.cpp の 146 行で定義されています。
|
inlinevirtual |
iksolver.h の 139 行で定義されています。
|
inlineprotected |
iksolver.h の 264 行で定義されています。
|
inlineprotected |
iksolver.h の 267 行で定義されています。
|
pure virtual |
Return a joint configuration for the given end effector transform.
[in] | param | the 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] | q0 | Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is NULL, returns the first solution found |
[in] | filteroptions | A bitmask of IkFilterOptions values controlling what is checked for each ik solution. |
[out] | solution | [optional] Holds the IK solution |
|
virtual |
Return a joint configuration for the given end effector transform.
[in] | param | the 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] | q0 | Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is NULL, returns the first solution found |
[in] | filteroptions | A bitmask of IkFilterOptions values controlling what is checked for each ik solution. |
[out] | ikreturn | Holds all the ik output data (including ik solutions) from the many processes involved in solving ik. |
iksolver.cpp の 84 行で定義されています。
|
inlinevirtual |
iksolver.h の 193 行で定義されています。
|
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
[in] | param | the 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] | q0 | Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is empty, returns the first solution found |
[in] | vFreeParameters | The free parameters of the null space of the IK solutions. Always in range of [0,1] |
[in] | filteroptions | A 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 |
|
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
[in] | param | the 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] | q0 | Return a solution nearest to the given configuration q0 in terms of the joint distance. If q0 is empty, returns the first solution found |
[in] | vFreeParameters | The free parameters of the null space of the IK solutions. Always in range of [0,1] |
[in] | filteroptions | A bitmask of IkFilterOptions values controlling what is checked for each ik solution. |
[out] | ikreturn | Holds all the ik output data (including ik solutions) from the many processes involved in solving ik. |
iksolver.cpp の 115 行で定義されています。
|
inlinevirtual |
iksolver.h の 244 行で定義されています。
|
pure virtual |
Return all joint configurations for the given end effector transform.
[in] | param | the 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] | filteroptions | A bitmask of IkFilterOptions values controlling what is checked for each ik solution. |
[out] | solutions | All solutions within a reasonable discretization level of the free parameters. |
|
virtual |
Return all joint configurations for the given end effector transform.
[in] | param | the 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] | filteroptions | A bitmask of IkFilterOptions values controlling what is checked for each ik solution. |
[out] | ikreturns | Holds all the ik output data (including ik solutions) from the many processes involved in solving ik. |
iksolver.cpp の 99 行で定義されています。
|
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
[in] | param | the 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] | vFreeParameters | The free parameters of the null space of the IK solutions. Always in range of [0,1] |
[in] | filteroptions | A bitmask of IkFilterOptions values controlling what is checked for each ik solution. |
[out] | solutions | All solutions within a reasonable discretization level of the free parameters. |
|
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
[in] | param | the 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] | vFreeParameters | The free parameters of the null space of the IK solutions. Always in range of [0,1] |
[in] | filteroptions | A bitmask of IkFilterOptions values controlling what is checked for each ik solution. |
[out] | ikreturns | Holds all the ik output data (including ik solutions) from the many processes involved in solving ik. |
iksolver.cpp の 130 行で定義されています。
|
virtual |
returns true if the solver supports a particular ik parameterization as input.