DART
6.7.3
|
A base class for IkFast-based analytical inverse kinematics classes. More...
#include <IkFast.hpp>
Public Types | |
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... | |
auto | computeSolutions (const Eigen::Isometry3d &desiredBodyTf) -> const std::vector< InverseKinematics::Analytical::Solution > &override |
Use this function to fill the entries of the mSolutions variable. More... | |
auto | getDofs () const -> const std::vector< std::size_t > &override |
Get a list of the DOFs that will be included in the entries of the solutions returned by getSolutions(). More... | |
virtual bool | isConfigured () const |
Returns true if this IkFast is ready to solve. More... | |
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. More... | |
ExtraDofUtilization | getExtraDofUtilization () const |
Get how extra DOFs are being utilized by the IK module. More... | |
void | setExtraErrorLengthClamp (double _clamp) |
Set how much to clamp the error vector that gets applied to extra DOFs. More... | |
double | getExtraErrorLengthClamp () const |
Get how much we will clamp the error vector that gets applied to extra DOFs. More... | |
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. More... | |
Properties | getAnalyticalProperties () const |
Get the Properties for this Analytical class. More... | |
void | constructDofMap () |
Construct a mapping from the DOFs of getDofs() to their indices within the Node's list of dependent DOFs. More... | |
virtual std::unique_ptr< GradientMethod > | clone (InverseKinematics *_newIK) const =0 |
Enable this GradientMethod to be cloned to a new IK module. More... | |
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. More... | |
void | clampGradient (Eigen::VectorXd &_grad) const |
Clamp the gradient based on the clamp settings of this GradientMethod. More... | |
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. More... | |
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. More... | |
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. More... | |
void | clearCache () |
Clear the cache to force the gradient to be recomputed. More... | |
InverseKinematics * | getIK () |
Returns the IK module that this GradientMethod belongs to. More... | |
const InverseKinematics * | getIK () const |
Returns the IK module that this GradientMethod belongs to. More... | |
Protected Member Functions | |
virtual int | getNumFreeParameters () const =0 |
virtual int * | getFreeParameters () const =0 |
virtual int | getNumJoints () const =0 |
virtual int | getIkRealSize () const =0 |
virtual int | getIkType () const =0 |
virtual bool | computeIk (const IkReal *mTargetTranspose, const IkReal *mTargetRotation, const IkReal *pfree, ikfast::IkSolutionListBase< IkReal > &solutions)=0 |
Computes the inverse kinematics solutions using the generated IKFast code. More... | |
virtual const char * | getKinematicsHash ()=0 |
virtual const char * | getIkFastVersion ()=0 |
virtual void | configure () const |
Configure IkFast. More... | |
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... | |
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 | |
std::vector< double > | mFreeParams |
bool | mConfigured |
True if this IkFast is ready to solve. More... | |
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... | |
std::vector< Solution > | mSolutions |
Vector of solutions. More... | |
UniqueProperties | mAnalyticalP |
Properties for this Analytical IK solver. More... | |
common::sub_ptr< InverseKinematics > | mIK |
The IK module that this GradientMethod belongs to. More... | |
std::string | mMethodName |
The name of this method. More... | |
Eigen::VectorXd | mLastPositions |
The last positions that was passed to this GradientMethod. More... | |
Eigen::VectorXd | mLastGradient |
The last gradient that was computed by this GradientMethod. More... | |
Properties | mGradientP |
Properties for this GradientMethod. More... | |
std::set< Observer * > | mObservers |
List of current Observers. More... | |
Private Attributes | |
std::array< IkReal, 9 > | mTargetRotation |
Cache data for the target rotation used by IKFast. More... | |
std::array< IkReal, 3 > | mTargetTranspose |
Cache data for the target translation used by IKFast. More... | |
std::vector< int > | mDofMap |
This maps the DOFs provided by getDofs() to their index in the Node's list of dependent DOFs. More... | |
std::vector< std::size_t > | mExtraDofs |
List of extra DOFs in the module which are not covered by the Analytical IK implementation. More... | |
std::vector< Solution > | mValidSolutionsCache |
A cache for the valid solutions. More... | |
std::vector< Solution > | mOutOfReachCache |
A cache for the out of reach solutions. More... | |
std::vector< Solution > | mLimitViolationCache |
A cache for solutions that violate joint limits. More... | |
Eigen::VectorXd | mConfigCache |
A cache for storing the current configuration. More... | |
Eigen::VectorXd | mRestoreConfigCache |
A cache for storing the current configuration so that it can be restored later. More... | |
Eigen::VectorXd | mExtraDofGradCache |
A cache for storing the gradient for the extra DOFs. More... | |
Eigen::VectorXd | mInitialPositionsCache |
Cache used by convertJacobianMethodOutputToGradient to avoid reallocating this vector on each iteration. More... | |
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/
|
inherited |
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.
This enumeration is used to indicate whether you want those DOFs to be used before applying the analytical solution, after applying the analytical solution, or not be used at all.
Jacobian transpose is used for the extra DOFs because it is inexpensive and robust to degenerate Jacobians which are common in low dimensional joint spaces. The primary advantage of pseudoinverse methods over Jacobian transpose methods is their precision, but analytical methods are even more precise than pseudoinverse methods, so that precision is not needed in this case.
If you want the extra DOFs to use a different method than Jacobian transpose, you can create two seperate IK modules (one which is analytical and one with the iterative method of your choice) and combine them in a HierarchicalIK.
Enumerator | |
---|---|
UNUSED | |
PRE_ANALYTICAL | |
POST_ANALYTICAL | |
PRE_AND_POST_ANALYTICAL |
|
inherited |
Bitwise enumerations that are used to describe some properties of each solution produced by the analytical IK.
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.
[in] | ik | The parent InverseKinematics solver that is associated with this gradient method. |
[in] | dofMap | The 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] | freeDofMap | The indices to the DOFs that are not solved by the IkFast solver. The values of these DOFs should be set properly. |
[in] | methodName | The name of this analytical inverse kinematics method. |
[in] | properties | Properties of InverseKinematics::Analytical. |
|
protectedvirtualinherited |
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.
You can override this function to customize how the extra DOFs are used. The default behavior is to use a simple Jacobian Transpose method.
The utilization flag will be PRE_ANALYTICAL if the function is being called before the Analytical solution is computed; it will be POST_ANALYTICAL if the function is being called after the Analytical solution is computed.
|
protectedinherited |
Add an Observer to the list of Observers.
|
inherited |
Apply weights to the gradient based on the weight settings of this GradientMethod.
|
protectedinherited |
Go through the mSolutions vector and tag entries with LIMIT_VIOLATED if any components of their configuration are outside of their position limits.
This will NOT clear the LIMIT_VIOLATED flag from entries of mSolutions which are already tagged with it, even if they do not violate any limits.
|
inherited |
Clamp the gradient based on the clamp settings of this GradientMethod.
|
inherited |
Clear the cache to force the gradient to be recomputed.
It should generally not be necessary to call this function.
|
pure virtualinherited |
Enable this GradientMethod to be cloned to a new IK module.
Implemented in dart::dynamics::SharedLibraryIkFast, dart::dynamics::InverseKinematics::JacobianTranspose, and dart::dynamics::InverseKinematics::JacobianDLS.
|
overridevirtualinherited |
You should not need to override this function.
Instead, you should override computeSolutions.
Implements dart::dynamics::InverseKinematics::GradientMethod.
|
protectedpure virtual |
Computes the inverse kinematics solutions using the generated IKFast code.
Implemented in dart::dynamics::SharedLibraryIkFast.
|
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.
|
protectedvirtual |
Configure IkFast.
If it's successfully configured, isConfigured() returns true.
Reimplemented in dart::dynamics::SharedLibraryIkFast.
|
inherited |
Construct a mapping from the DOFs of getDofs() to their indices within the Node's list of dependent DOFs.
This will be called immediately after the Analytical is constructed; this one call is sufficient as long as the DOFs of Analytical::getDofs() is not changed. However, if your Analytical is able to change the DOFs that it operates on, then you will need to call this function each time the DOFs have changed.
|
inherited |
Convert the gradient that gets generated by Jacobian methods into a gradient that can be used by a GradientDescentSolver.
Not all Joint types can be integrated using standard addition (e.g. FreeJoint and BallJoint), therefore Jacobian-based differential methods will tend to generate gradients that cannot be correctly used by a simple addition-based GradientDescentSolver. Running your gradient through this function before returning it will make the gradient suitable for a standard solver.
|
inherited |
This function is used to handle caching the gradient vector and interfacing with the solver.
|
inherited |
Get the Properties for this Analytical class.
|
inherited |
Get the weights of this GradientMethod.
|
inherited |
Get the component-wise clamp for this GradientMethod.
|
overridevirtual |
Get a list of the DOFs that will be included in the entries of the solutions returned by getSolutions().
Ideally, this should match up with the DOFs being used by the InverseKinematics module, but this might not always be possible, so this function ensures that solutions can be interpreted correctly.
Implements dart::dynamics::InverseKinematics::Analytical.
|
inherited |
Get how extra DOFs are being utilized by the IK module.
|
inherited |
Get how much we will clamp the error vector that gets applied to extra DOFs.
|
protectedpure virtual |
Implemented in dart::dynamics::SharedLibraryIkFast.
|
inherited |
Get the Properties of this GradientMethod.
|
inherited |
Returns the IK module that this GradientMethod belongs to.
|
inherited |
Returns the IK module that this GradientMethod belongs to.
|
protectedpure virtual |
Implemented in dart::dynamics::SharedLibraryIkFast.
|
protectedpure virtual |
Implemented in dart::dynamics::SharedLibraryIkFast.
|
protectedpure virtual |
Implemented in dart::dynamics::SharedLibraryIkFast.
|
protectedpure virtual |
Implemented in dart::dynamics::SharedLibraryIkFast.
|
inherited |
Get the name of this GradientMethod.
|
protectedpure virtual |
Implemented in dart::dynamics::SharedLibraryIkFast.
|
protectedpure virtual |
Implemented in dart::dynamics::SharedLibraryIkFast.
|
inherited |
Get the configuration of the DOFs.
The components of this vector will correspond to the DOFs provided by getDofs().
|
inherited |
Get the solutions for this IK module, along with a tag indicating whether each solution is valid.
This function will assume that you want to use the desired transform given by the IK module's current ErrorMethod.
|
inherited |
Get the solutions for this IK module, along with a tag indicating whether each solution is valid.
This function will compute the configurations using the given desired transform instead of using the IK module's current ErrorMethod.
|
virtual |
Returns true if this IkFast is ready to solve.
|
protectedinherited |
Remove an Observer from the list of Observers.
|
inherited |
Reset the quality comparison function to the default method.
|
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.
|
inherited |
Set the weights that will be applied to each component of the gradient.
If the number of components in _weights is smaller than the number of components in the gradient, then a weight of 1.0 will be applied to all components that are out of the range of _weights. Passing in an empty vector for _weights will effectively make all the gradient components unweighted.
|
inherited |
Set the component-wise clamp for this GradientMethod.
Each component of the gradient will be individually clamped to this size.
|
inherited |
Set how you want extra DOFs to be utilized by the IK module.
|
inherited |
Set how much to clamp the error vector that gets applied to extra DOFs.
|
inherited |
Set the configuration of the DOFs.
The components of _config must correspond to the DOFs provided by getDofs().
|
inherited |
Set the function that will be used to compare the qualities of two solutions.
This function should return true if the first argument is a better solution than the second argument.
By default, it will prefer the solution which has the smallest size for its largest change in joint angle. In other words, for each configuration that it is given, it will compare the largest change in joint angle for each configuration and pick the one that is smallest.
Note that outside of this comparison function, the Solutions will be split between which are valid, which are out-of-reach, and which are in violation of joint limits. Valid solutions will always be ranked above invalid solutions, and joint limit violations will always be ranked last.
|
protectedinherited |
Properties for this Analytical IK solver.
|
privateinherited |
A cache for storing the current configuration.
|
mutableprotected |
True if this IkFast is ready to solve.
|
privateinherited |
This maps the DOFs provided by getDofs() to their index in the Node's list of dependent DOFs.
This map is constructed by constructDofMap().
|
mutableprotected |
Indices of the DegreeOfFreedoms associated to the variable parameters of this IkFast.
|
privateinherited |
A cache for storing the gradient for the extra DOFs.
|
privateinherited |
List of extra DOFs in the module which are not covered by the Analytical IK implementation.
The index of each DOF is its dependency index in the JacobianNode (i.e. the column it applies to in the Node's Jacobian).
|
mutableprotected |
Indices of the DegreeOfFreedoms associated to the free parameters of this IkFast.
|
mutableprotected |
|
protectedinherited |
Properties for this GradientMethod.
|
protectedinherited |
The IK module that this GradientMethod belongs to.
|
privateinherited |
Cache used by convertJacobianMethodOutputToGradient to avoid reallocating this vector on each iteration.
|
protectedinherited |
The last gradient that was computed by this GradientMethod.
|
protectedinherited |
The last positions that was passed to this GradientMethod.
|
privateinherited |
A cache for solutions that violate joint limits.
|
protectedinherited |
The name of this method.
|
mutableprotectedinherited |
List of current Observers.
|
privateinherited |
A cache for the out of reach solutions.
|
privateinherited |
A cache for storing the current configuration so that it can be restored later.
This is different from mConfigCache which will not be used to restore the configuration.
|
protectedinherited |
Vector of solutions.
|
private |
Cache data for the target rotation used by IKFast.
|
private |
Cache data for the target translation used by IKFast.
|
privateinherited |
A cache for the valid solutions.
The valid and invalid solution caches are kept separate so that they can each be sorted by quality individually. Valid solutions will always be at the top of mFinalResults even if their quality is scored below the invalid solutions.