dart
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dart::dynamics::IkFast Class Referenceabstract

A base class for IkFast-based analytical inverse kinematics classes. More...

#include <IkFast.hpp>

Inheritance diagram for dart::dynamics::IkFast:
Inheritance graph
[legend]
Collaboration diagram for dart::dynamics::IkFast:
Collaboration graph
[legend]

Public Types

enum  IkType {
  TRANSFORM_6D, ROTATION_3D, TRANSLATION_3D, DIRECTION_3D,
  RAY_4D, LOOKAT_3D, TRANSLATION_DIRECTION_5D, TRANSLATION_XY_2D,
  TRANSLATION_XY_ORIENTATION_3D, TRANSLATION_LOCAL_GLOBAL_6D, TRANSLATION_X_AXIS_ANGLE_4D, TRANSLATION_Y_AXIS_ANGLE_4D,
  TRANSLATION_Z_AXIS_ANGLE_4D, TRANSLATION_X_AXIS_ANGLE_Z_NORM_4D, TRANSLATION_Y_AXIS_ANGLE_X_NORM_4D, TRANSLATION_Z_AXIS_ANGLE_Y_NORM_4D,
  UNKNOWN
}
 Inverse kinematics types supported by IkFast. More...
 
- Public Types inherited from dart::dynamics::InverseKinematics::Analytical
enum  Validity_t { VALID = 0, OUT_OF_REACH = 1 << 0, LIMIT_VIOLATED = 1 << 1 }
 Bitwise enumerations that are used to describe some properties of each solution produced by the analytical IK. More...
 
enum  ExtraDofUtilization { UNUSED = 0, PRE_ANALYTICAL, POST_ANALYTICAL, PRE_AND_POST_ANALYTICAL }
 If there are extra DOFs in the IK module which your Analytical solver implementation does not make use of, those DOFs can be used to supplement the analytical solver using Jacobian transpose iteration. More...
 
typedef std::function< bool(const Eigen::VectorXd &_better, const Eigen::VectorXd &_worse, const InverseKinematics *_ik)> QualityComparison
 

Public Member Functions

 IkFast (InverseKinematics *ik, const std::vector< std::size_t > &dofMap, const std::vector< std::size_t > &freeDofMap, const std::string &methodName="IKFast", const Analytical::Properties &properties=Analytical::Properties())
 Constructor. More...
 
const std::vector< InverseKinematics::Analytical::Solution > & computeSolutions (const Eigen::Isometry3d &desiredBodyTf) override
 Use this function to fill the entries of the mSolutions variable. More...
 
Eigen::Isometry3d computeFk (const Eigen::VectorXd &parameters)
 Computes forward kinematics given joint positions where the dimension is the same as getNumJoints2(). More...
 
const std::vector< std::size_t > & getDofs () const override
 Returns the indices of the DegreeOfFreedoms that are part of the joints that IkFast solves for. More...
 
const std::vector< std::size_t > & getFreeDofs () const
 Returns the indices of the DegreeOfFreedoms that are part of the joints that IkFast solves but the values should be set by the user in prior. More...
 
virtual bool isConfigured () const
 Returns true if this IkFast is ready to solve.
 
std::size_t getNumFreeParameters2 () const
 Returns the number of free parameters users has to set apriori.
 
std::size_t getNumJoints2 () const
 Returns the total number of indices of the chane.
 
IkType getIkType2 () const
 Returns the IK type.
 
const std::string getKinematicsHash2 () const
 Returns a hash of all the chain values used for double checking that the correct IK is used. More...
 
std::string getIkFastVersion2 () const
 Returns the IkFast version used to generate this file.
 
- Public Member Functions inherited from dart::dynamics::InverseKinematics::Analytical
 Analytical (InverseKinematics *_ik, const std::string &_methodName, const Properties &_properties)
 Constructor.
 
virtual ~Analytical ()=default
 Virtual destructor.
 
const std::vector< Solution > & getSolutions ()
 Get the solutions for this IK module, along with a tag indicating whether each solution is valid. More...
 
const std::vector< Solution > & getSolutions (const Eigen::Isometry3d &_desiredTf)
 Get the solutions for this IK module, along with a tag indicating whether each solution is valid. More...
 
void computeGradient (const Eigen::Vector6d &_error, Eigen::VectorXd &_grad) override
 You should not need to override this function. More...
 
void setPositions (const Eigen::VectorXd &_config)
 Set the configuration of the DOFs. More...
 
Eigen::VectorXd getPositions () const
 Get the configuration of the DOFs. More...
 
void setExtraDofUtilization (ExtraDofUtilization _utilization)
 Set how you want extra DOFs to be utilized by the IK module.
 
ExtraDofUtilization getExtraDofUtilization () const
 Get how extra DOFs are being utilized by the IK module.
 
void setExtraErrorLengthClamp (double _clamp)
 Set how much to clamp the error vector that gets applied to extra DOFs.
 
double getExtraErrorLengthClamp () const
 Get how much we will clamp the error vector that gets applied to extra DOFs.
 
void setQualityComparisonFunction (const QualityComparison &_func)
 Set the function that will be used to compare the qualities of two solutions. More...
 
void resetQualityComparisonFunction ()
 Reset the quality comparison function to the default method.
 
Properties getAnalyticalProperties () const
 Get the Properties for this Analytical class.
 
void constructDofMap ()
 Construct a mapping from the DOFs of getDofs() to their indices within the Node's list of dependent DOFs. More...
 
- Public Member Functions inherited from dart::dynamics::InverseKinematics::GradientMethod
 GradientMethod (InverseKinematics *_ik, const std::string &_methodName, const Properties &_properties)
 Constructor.
 
virtual ~GradientMethod ()=default
 Virtual destructor.
 
virtual std::unique_ptr< GradientMethodclone (InverseKinematics *_newIK) const =0
 Enable this GradientMethod to be cloned to a new IK module.
 
void evalGradient (const Eigen::VectorXd &_q, Eigen::Map< Eigen::VectorXd > _grad)
 This function is used to handle caching the gradient vector and interfacing with the solver. More...
 
const std::string & getMethodName () const
 Get the name of this GradientMethod.
 
void clampGradient (Eigen::VectorXd &_grad) const
 Clamp the gradient based on the clamp settings of this GradientMethod.
 
void setComponentWiseClamp (double _clamp=DefaultIKGradientComponentClamp)
 Set the component-wise clamp for this GradientMethod. More...
 
double getComponentWiseClamp () const
 Get the component-wise clamp for this GradientMethod.
 
void applyWeights (Eigen::VectorXd &_grad) const
 Apply weights to the gradient based on the weight settings of this GradientMethod. More...
 
void setComponentWeights (const Eigen::VectorXd &_weights)
 Set the weights that will be applied to each component of the gradient. More...
 
const Eigen::VectorXd & getComponentWeights () const
 Get the weights of this GradientMethod.
 
void convertJacobianMethodOutputToGradient (Eigen::VectorXd &grad, const std::vector< std::size_t > &dofs)
 Convert the gradient that gets generated by Jacobian methods into a gradient that can be used by a GradientDescentSolver. More...
 
Properties getGradientMethodProperties () const
 Get the Properties of this GradientMethod.
 
void clearCache ()
 Clear the cache to force the gradient to be recomputed. More...
 
InverseKinematicsgetIK ()
 Returns the IK module that this GradientMethod belongs to.
 
const InverseKinematicsgetIK () const
 Returns the IK module that this GradientMethod belongs to.
 
- Public Member Functions inherited from dart::common::Subject
virtual ~Subject ()
 Destructor will notify all Observers that it is destructing.
 

Protected Member Functions

virtual int getNumFreeParameters () const =0
 Returns the number of free parameters users has to set apriori.
 
virtual int * getFreeParameters () const =0
 Returns the indicies of the free parameters indexed by the chain joints.
 
virtual int getNumJoints () const =0
 Returns the total number of indices of the chane.
 
virtual int getIkRealSize () const =0
 Returns the size in bytes of the configured number type.
 
virtual int getIkType () const =0
 Returns the IK type.
 
virtual bool computeIk (const IkReal *targetTranspose, const IkReal *targetRotation, const IkReal *pfree, ikfast::IkSolutionListBase< IkReal > &solutions)=0
 Computes the inverse kinematics solutions using the generated IKFast code.
 
virtual void computeFk (const IkReal *parameters, IkReal *targetTranspose, IkReal *targetRotation)=0
 Computes the forward kinematics solutions using the generated IKFast code.
 
virtual const char * getKinematicsHash ()=0
 Returns a hash of all the chain values used for double checking that the correct IK is used. More...
 
virtual const char * getIkFastVersion ()=0
 Returns the IkFast version used to generate this file.
 
virtual void configure () const
 Configure IkFast. More...
 
- Protected Member Functions inherited from dart::dynamics::InverseKinematics::Analytical
virtual void addExtraDofGradient (Eigen::VectorXd &grad, const Eigen::Vector6d &error, ExtraDofUtilization utilization)
 This function will compute a gradient which utilizes the extra DOFs that go unused by the Analytical solution and then it will add the components of that gradient to the output parameter: grad. More...
 
void checkSolutionJointLimits ()
 Go through the mSolutions vector and tag entries with LIMIT_VIOLATED if any components of their configuration are outside of their position limits. More...
 
- Protected Member Functions inherited from dart::common::Subject
void sendDestructionNotification () const
 Send a destruction notification to all Observers. More...
 
void addObserver (Observer *_observer) const
 Add an Observer to the list of Observers.
 
void removeObserver (Observer *_observer) const
 Remove an Observer from the list of Observers.
 

Protected Attributes

std::vector< double > mFreeParams
 
bool mConfigured
 True if this IkFast is ready to solve.
 
std::vector< std::size_t > mDofs
 Indices of the DegreeOfFreedoms associated to the variable parameters of this IkFast. More...
 
std::vector< std::size_t > mFreeDofs
 Indices of the DegreeOfFreedoms associated to the free parameters of this IkFast. More...
 
- Protected Attributes inherited from dart::dynamics::InverseKinematics::Analytical
std::vector< SolutionmSolutions
 Vector of solutions.
 
UniqueProperties mAnalyticalP
 Properties for this Analytical IK solver.
 
- Protected Attributes inherited from dart::dynamics::InverseKinematics::GradientMethod
common::sub_ptr< InverseKinematicsmIK
 The IK module that this GradientMethod belongs to.
 
std::string mMethodName
 The name of this method.
 
Eigen::VectorXd mLastPositions
 The last positions that was passed to this GradientMethod.
 
Eigen::VectorXd mLastGradient
 The last gradient that was computed by this GradientMethod.
 
Properties mGradientP
 Properties for this GradientMethod.
 
- Protected Attributes inherited from dart::common::Subject
std::set< Observer * > mObservers
 List of current Observers.
 

Detailed Description

A base class for IkFast-based analytical inverse kinematics classes.

The detail of IkFast can be found here: http://openrave.org/docs/0.8.2/openravepy/ikfast/

Member Enumeration Documentation

◆ IkType

Inverse kinematics types supported by IkFast.

Enumerator
TRANSFORM_6D 

End effector reaches desired 6D transformation.

ROTATION_3D 

End effector reaches desired 3D rotation.

TRANSLATION_3D 

End effector origin reaches desired 3D translation.

DIRECTION_3D 

Direction on end effector coordinate system reaches desired direction.

RAY_4D 

Ray on end effector coordinate system reaches desired global ray.

LOOKAT_3D 

Direction on end effector coordinate system points to desired 3D position.

TRANSLATION_DIRECTION_5D 

End effector origin and direction reaches desired 3D translation and direction.

Can be thought of as Ray IK where the origin of the ray must coincide.

TRANSLATION_XY_2D 

End effector origin reaches desired XY translation position, Z is ignored.

The coordinate system with relative to the base link.

TRANSLATION_XY_ORIENTATION_3D 

2D translation along XY plane and 1D rotation around Z axis.

The offset of the rotation is measured starting at +X, so at +X is it 0, at +Y it is pi/2.

TRANSLATION_LOCAL_GLOBAL_6D 

Local point on end effector origin reaches desired 3D global point.

Because both local point and global point can be specified, there are 6 values.

TRANSLATION_X_AXIS_ANGLE_4D 

End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with x-axis (defined in the manipulator base link’s coordinate system)

TRANSLATION_Y_AXIS_ANGLE_4D 

End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with y-axis (defined in the manipulator base link’s coordinate system)

TRANSLATION_Z_AXIS_ANGLE_4D 

End effector origin reaches desired 3D translation, manipulator direction makes a specific angle with z-axis (defined in the manipulator base link’s coordinate system)

TRANSLATION_X_AXIS_ANGLE_Z_NORM_4D 

End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z-axis and be rotated at a certain angle starting from the x-axis (defined in the manipulator base link's coordinate system)

TRANSLATION_Y_AXIS_ANGLE_X_NORM_4D 

End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z-axis and be rotated at a certain angle starting from the y-axis (defined in the manipulator base link's coordinate system)

TRANSLATION_Z_AXIS_ANGLE_Y_NORM_4D 

End effector origin reaches desired 3D translation, manipulator direction needs to be orthogonal to z-axis and be rotated at a certain angle starting from the z-axis (defined in the manipulator base link's coordinate system)

Constructor & Destructor Documentation

◆ IkFast()

dart::dynamics::IkFast::IkFast ( InverseKinematics ik,
const std::vector< std::size_t > &  dofMap,
const std::vector< std::size_t > &  freeDofMap,
const std::string &  methodName = "IKFast",
const Analytical::Properties &  properties = Analytical::Properties() 
)

Constructor.

Parameters
[in]ikThe parent InverseKinematics solver that is associated with this gradient method.
[in]dofMapThe indices to the degrees-of-freedom that will be solved by IkFast. The number of DOFs can be varied depending on the IkFast solvers.
[in]freeDofMapThe indices to the DOFs that are not solved by the IkFast solver. The values of these DOFs should be set properly.
[in]methodNameThe name of this analytical inverse kinematics method.
[in]propertiesProperties of InverseKinematics::Analytical.

Member Function Documentation

◆ computeFk()

Eigen::Isometry3d dart::dynamics::IkFast::computeFk ( const Eigen::VectorXd &  parameters)

Computes forward kinematics given joint positions where the dimension is the same as getNumJoints2().

◆ computeSolutions()

auto dart::dynamics::IkFast::computeSolutions ( const Eigen::Isometry3d &  _desiredBodyTf)
overridevirtual

Use this function to fill the entries of the mSolutions variable.

Be sure to clear the mSolutions vector at the start, and to also return the mSolutions vector at the end. Note that you are not expected to evaluate any of the solutions for their quality. However, you should set the Solution::mValidity flag to OUT_OF_REACH for each solution that does not actually reach the desired transform, and you should call checkSolutionJointLimits() and the end of the function, which will set the LIMIT_VIOLATED flags of any configurations that are outside of the position limits.

Implements dart::dynamics::InverseKinematics::Analytical.

◆ configure()

void dart::dynamics::IkFast::configure ( ) const
protectedvirtual

Configure IkFast.

If it's successfully configured, isConfigured() returns true.

Reimplemented in dart::dynamics::SharedLibraryIkFast.

◆ getDofs()

auto dart::dynamics::IkFast::getDofs ( ) const
overridevirtual

Returns the indices of the DegreeOfFreedoms that are part of the joints that IkFast solves for.

Implements dart::dynamics::InverseKinematics::Analytical.

◆ getFreeDofs()

const std::vector< std::size_t > & dart::dynamics::IkFast::getFreeDofs ( ) const

Returns the indices of the DegreeOfFreedoms that are part of the joints that IkFast solves but the values should be set by the user in prior.

◆ getKinematicsHash()

virtual const char* dart::dynamics::IkFast::getKinematicsHash ( )
protectedpure virtual

Returns a hash of all the chain values used for double checking that the correct IK is used.

Implemented in dart::dynamics::SharedLibraryIkFast, and SharedLibraryWamIkFast.

◆ getKinematicsHash2()

const std::string dart::dynamics::IkFast::getKinematicsHash2 ( ) const

Returns a hash of all the chain values used for double checking that the correct IK is used.

Member Data Documentation

◆ mDofs

std::vector<std::size_t> dart::dynamics::IkFast::mDofs
mutableprotected

Indices of the DegreeOfFreedoms associated to the variable parameters of this IkFast.

◆ mFreeDofs

std::vector<std::size_t> dart::dynamics::IkFast::mFreeDofs
mutableprotected

Indices of the DegreeOfFreedoms associated to the free parameters of this IkFast.


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