DART  6.6.2
dart::dynamics::InverseKinematics::ErrorMethod Class Referenceabstract

ErrorMethod is a base class for different ways of computing the error of an InverseKinematics module. More...

#include <InverseKinematics.hpp>

Inheritance diagram for dart::dynamics::InverseKinematics::ErrorMethod:
dart::common::Subject dart::dynamics::InverseKinematics::TaskSpaceRegion

Classes

struct  Properties
 The Properties struct contains settings that are commonly used by methods that compute error for inverse kinematics. More...
 

Public Types

typedef std::pair< Eigen::Vector6d, Eigen::Vector6dBounds
 

Public Member Functions

 ErrorMethod (InverseKinematics *_ik, const std::string &_methodName, const Properties &_properties=Properties())
 Constructor. More...
 
virtual ~ErrorMethod ()=default
 Virtual destructor. More...
 
virtual std::unique_ptr< ErrorMethodclone (InverseKinematics *_newIK) const =0
 Enable this ErrorMethod to be cloned to a new IK module. More...
 
virtual Eigen::Vector6d computeError ()=0
 Override this function with your implementation of the error vector computation. More...
 
virtual Eigen::Isometry3d computeDesiredTransform (const Eigen::Isometry3d &_currentTf, const Eigen::Vector6d &_error)=0
 Override this function with your implementation of computing the desired given the current transform and error vector. More...
 
const Eigen::Vector6devalError (const Eigen::VectorXd &_q)
 This function is used to handle caching the error vector. More...
 
const std::string & getMethodName () const
 Get the name of this ErrorMethod. More...
 
void setBounds (const Eigen::Vector6d &_lower=Eigen::Vector6d::Constant(-DefaultIKTolerance), const Eigen::Vector6d &_upper=Eigen::Vector6d::Constant(DefaultIKTolerance))
 Set all the error bounds. More...
 
void setBounds (const std::pair< Eigen::Vector6d, Eigen::Vector6d > &_bounds)
 Set all the error bounds. More...
 
const std::pair< Eigen::Vector6d, Eigen::Vector6d > & getBounds () const
 Get all the error bounds. More...
 
void setAngularBounds (const Eigen::Vector3d &_lower=Eigen::Vector3d::Constant(-DefaultIKTolerance), const Eigen::Vector3d &_upper=Eigen::Vector3d::Constant(DefaultIKTolerance))
 Set the error bounds for orientation. More...
 
void setAngularBounds (const std::pair< Eigen::Vector3d, Eigen::Vector3d > &_bounds)
 Set the error bounds for orientation. More...
 
std::pair< Eigen::Vector3d, Eigen::Vector3d > getAngularBounds () const
 Get the error bounds for orientation. More...
 
void setLinearBounds (const Eigen::Vector3d &_lower=Eigen::Vector3d::Constant(-DefaultIKTolerance), const Eigen::Vector3d &_upper=Eigen::Vector3d::Constant(DefaultIKTolerance))
 Set the error bounds for translation. More...
 
void setLinearBounds (const std::pair< Eigen::Vector3d, Eigen::Vector3d > &_bounds)
 Set the error bounds for translation. More...
 
std::pair< Eigen::Vector3d, Eigen::Vector3d > getLinearBounds () const
 Get the error bounds for translation. More...
 
void setErrorLengthClamp (double _clampSize=DefaultIKErrorClamp)
 Set the clamp that will be applied to the length of the error vector each iteration. More...
 
double getErrorLengthClamp () const
 Set the clamp that will be applied to the length of the error vector each iteration. More...
 
void setErrorWeights (const Eigen::Vector6d &_weights)
 Set the weights that will be applied to each component of the error vector. More...
 
const Eigen::Vector6dgetErrorWeights () const
 Get the weights that will be applied to each component of the error vector. More...
 
void setAngularErrorWeights (const Eigen::Vector3d &_weights=Eigen::Vector3d::Constant(DefaultIKAngularWeight))
 Set the weights that will be applied to each angular component of the error vector. More...
 
Eigen::Vector3d getAngularErrorWeights () const
 Get the weights that will be applied to each angular component of the error vector. More...
 
void setLinearErrorWeights (const Eigen::Vector3d &_weights=Eigen::Vector3d::Constant(DefaultIKLinearWeight))
 Set the weights that will be applied to each linear component of the error vector. More...
 
Eigen::Vector3d getLinearErrorWeights () const
 Get the weights that will be applied to each linear component of the error vector. More...
 
Properties getErrorMethodProperties () const
 Get the Properties of this ErrorMethod. More...
 
void clearCache ()
 Clear the cache to force the error to be recomputed. More...
 

Protected Member Functions

void sendDestructionNotification () const
 Send a destruction notification to all Observers. More...
 
void addObserver (Observer *_observer) const
 Add an Observer to the list of Observers. More...
 
void removeObserver (Observer *_observer) const
 Remove an Observer from the list of Observers. More...
 

Protected Attributes

common::sub_ptr< InverseKinematicsmIK
 Pointer to the IK module of this ErrorMethod. More...
 
std::string mMethodName
 Name of this error method. More...
 
Eigen::VectorXd mLastPositions
 The last joint positions passed into this ErrorMethod. More...
 
Eigen::Vector6d mLastError
 The last error vector computed by this ErrorMethod. More...
 
Properties mErrorP
 The properties of this ErrorMethod. More...
 
std::set< Observer * > mObservers
 List of current Observers. More...
 

Detailed Description

ErrorMethod is a base class for different ways of computing the error of an InverseKinematics module.

Member Typedef Documentation

◆ Bounds

Constructor & Destructor Documentation

◆ ErrorMethod()

dart::dynamics::InverseKinematics::ErrorMethod::ErrorMethod ( InverseKinematics _ik,
const std::string &  _methodName,
const Properties _properties = Properties() 
)

Constructor.

◆ ~ErrorMethod()

virtual dart::dynamics::InverseKinematics::ErrorMethod::~ErrorMethod ( )
virtualdefault

Virtual destructor.

Member Function Documentation

◆ addObserver()

void dart::common::Subject::addObserver ( Observer _observer) const
protectedinherited

Add an Observer to the list of Observers.

◆ clearCache()

void dart::dynamics::InverseKinematics::ErrorMethod::clearCache ( )

Clear the cache to force the error to be recomputed.

It should generally not be necessary to call this function.

◆ clone()

virtual std::unique_ptr<ErrorMethod> dart::dynamics::InverseKinematics::ErrorMethod::clone ( InverseKinematics _newIK) const
pure virtual

Enable this ErrorMethod to be cloned to a new IK module.

Implemented in dart::dynamics::InverseKinematics::TaskSpaceRegion.

◆ computeDesiredTransform()

Eigen::Isometry3d dart::dynamics::InverseKinematics::ErrorMethod::computeDesiredTransform ( const Eigen::Isometry3d &  _currentTf,
const Eigen::Vector6d _error 
)
pure virtual

Override this function with your implementation of computing the desired given the current transform and error vector.

If you want the desired transform to always be equal to the Target's transform, you can simply call ErrorMethod::computeDesiredTransform to implement this function.

Implemented in dart::dynamics::InverseKinematics::TaskSpaceRegion.

◆ computeError()

virtual Eigen::Vector6d dart::dynamics::InverseKinematics::ErrorMethod::computeError ( )
pure virtual

Override this function with your implementation of the error vector computation.

The expectation is that the first three components of the vector will correspond to orientation error (in an angle-axis format) while the last three components correspond to translational error.

When implementing this function, you should assume that the Skeleton's current joint positions corresponds to the positions that you must use to compute the error. This function will only get called when an update is needed.

Implemented in dart::dynamics::InverseKinematics::TaskSpaceRegion.

◆ evalError()

const Eigen::Vector6d & dart::dynamics::InverseKinematics::ErrorMethod::evalError ( const Eigen::VectorXd &  _q)

This function is used to handle caching the error vector.

◆ getAngularBounds()

std::pair< Eigen::Vector3d, Eigen::Vector3d > dart::dynamics::InverseKinematics::ErrorMethod::getAngularBounds ( ) const

Get the error bounds for orientation.

◆ getAngularErrorWeights()

Eigen::Vector3d dart::dynamics::InverseKinematics::ErrorMethod::getAngularErrorWeights ( ) const

Get the weights that will be applied to each angular component of the error vector.

◆ getBounds()

const std::pair< Eigen::Vector6d, Eigen::Vector6d > & dart::dynamics::InverseKinematics::ErrorMethod::getBounds ( ) const

Get all the error bounds.

◆ getErrorLengthClamp()

double dart::dynamics::InverseKinematics::ErrorMethod::getErrorLengthClamp ( ) const

Set the clamp that will be applied to the length of the error vector each iteration.

◆ getErrorMethodProperties()

InverseKinematics::ErrorMethod::Properties dart::dynamics::InverseKinematics::ErrorMethod::getErrorMethodProperties ( ) const

Get the Properties of this ErrorMethod.

◆ getErrorWeights()

const Eigen::Vector6d & dart::dynamics::InverseKinematics::ErrorMethod::getErrorWeights ( ) const

Get the weights that will be applied to each component of the error vector.

◆ getLinearBounds()

std::pair< Eigen::Vector3d, Eigen::Vector3d > dart::dynamics::InverseKinematics::ErrorMethod::getLinearBounds ( ) const

Get the error bounds for translation.

◆ getLinearErrorWeights()

Eigen::Vector3d dart::dynamics::InverseKinematics::ErrorMethod::getLinearErrorWeights ( ) const

Get the weights that will be applied to each linear component of the error vector.

◆ getMethodName()

const std::string & dart::dynamics::InverseKinematics::ErrorMethod::getMethodName ( ) const

Get the name of this ErrorMethod.

◆ removeObserver()

void dart::common::Subject::removeObserver ( Observer _observer) const
protectedinherited

Remove an Observer from the list of Observers.

◆ sendDestructionNotification()

void dart::common::Subject::sendDestructionNotification ( ) const
protectedinherited

Send a destruction notification to all Observers.

This will cause all Observers to behave as if this Subject has been permanently deleted, so it should only be called when that behavior is desired.

◆ setAngularBounds() [1/2]

void dart::dynamics::InverseKinematics::ErrorMethod::setAngularBounds ( const Eigen::Vector3d &  _lower = Eigen::Vector3d::Constant(-DefaultIKTolerance),
const Eigen::Vector3d &  _upper = Eigen::Vector3d::Constant( DefaultIKTolerance) 
)

Set the error bounds for orientation.

◆ setAngularBounds() [2/2]

void dart::dynamics::InverseKinematics::ErrorMethod::setAngularBounds ( const std::pair< Eigen::Vector3d, Eigen::Vector3d > &  _bounds)

Set the error bounds for orientation.

◆ setAngularErrorWeights()

void dart::dynamics::InverseKinematics::ErrorMethod::setAngularErrorWeights ( const Eigen::Vector3d &  _weights = Eigen::Vector3d::Constant(DefaultIKAngularWeight))

Set the weights that will be applied to each angular component of the error vector.

◆ setBounds() [1/2]

void dart::dynamics::InverseKinematics::ErrorMethod::setBounds ( const Eigen::Vector6d _lower = Eigen::Vector6d::Constant(-DefaultIKTolerance),
const Eigen::Vector6d _upper = Eigen::Vector6d::Constant( DefaultIKTolerance) 
)

Set all the error bounds.

◆ setBounds() [2/2]

void dart::dynamics::InverseKinematics::ErrorMethod::setBounds ( const std::pair< Eigen::Vector6d, Eigen::Vector6d > &  _bounds)

Set all the error bounds.

◆ setErrorLengthClamp()

void dart::dynamics::InverseKinematics::ErrorMethod::setErrorLengthClamp ( double  _clampSize = DefaultIKErrorClamp)

Set the clamp that will be applied to the length of the error vector each iteration.

◆ setErrorWeights()

void dart::dynamics::InverseKinematics::ErrorMethod::setErrorWeights ( const Eigen::Vector6d _weights)

Set the weights that will be applied to each component of the error vector.

◆ setLinearBounds() [1/2]

void dart::dynamics::InverseKinematics::ErrorMethod::setLinearBounds ( const Eigen::Vector3d &  _lower = Eigen::Vector3d::Constant(-DefaultIKTolerance),
const Eigen::Vector3d &  _upper = Eigen::Vector3d::Constant( DefaultIKTolerance) 
)

Set the error bounds for translation.

◆ setLinearBounds() [2/2]

void dart::dynamics::InverseKinematics::ErrorMethod::setLinearBounds ( const std::pair< Eigen::Vector3d, Eigen::Vector3d > &  _bounds)

Set the error bounds for translation.

◆ setLinearErrorWeights()

void dart::dynamics::InverseKinematics::ErrorMethod::setLinearErrorWeights ( const Eigen::Vector3d &  _weights = Eigen::Vector3d::Constant(DefaultIKLinearWeight))

Set the weights that will be applied to each linear component of the error vector.

Member Data Documentation

◆ mErrorP

Properties dart::dynamics::InverseKinematics::ErrorMethod::mErrorP
protected

The properties of this ErrorMethod.

◆ mIK

common::sub_ptr<InverseKinematics> dart::dynamics::InverseKinematics::ErrorMethod::mIK
protected

Pointer to the IK module of this ErrorMethod.

◆ mLastError

Eigen::Vector6d dart::dynamics::InverseKinematics::ErrorMethod::mLastError
protected

The last error vector computed by this ErrorMethod.

◆ mLastPositions

Eigen::VectorXd dart::dynamics::InverseKinematics::ErrorMethod::mLastPositions
protected

The last joint positions passed into this ErrorMethod.

◆ mMethodName

std::string dart::dynamics::InverseKinematics::ErrorMethod::mMethodName
protected

Name of this error method.

◆ mObservers

std::set<Observer*> dart::common::Subject::mObservers
mutableprotectedinherited

List of current Observers.