dart
|
IkFast-based analytical inverse kinematics class. More...
#include <SharedLibraryIkFast.hpp>
Public Member Functions | |
SharedLibraryIkFast (InverseKinematics *ik, const std::string &filePath, 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 | clone (InverseKinematics *newIK) const -> std::unique_ptr< GradientMethod > override |
Enable this GradientMethod to be cloned to a new IK module. | |
![]() | |
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 ¶meters) |
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. | |
![]() | |
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... | |
![]() | |
GradientMethod (InverseKinematics *_ik, const std::string &_methodName, const Properties &_properties) | |
Constructor. | |
virtual | ~GradientMethod ()=default |
Virtual destructor. | |
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... | |
InverseKinematics * | getIK () |
Returns the IK module that this GradientMethod belongs to. | |
const InverseKinematics * | getIK () const |
Returns the IK module that this GradientMethod belongs to. | |
![]() | |
virtual | ~Subject () |
Destructor will notify all Observers that it is destructing. | |
Protected Types | |
using | IkFastFuncGetInt = int(*)() |
using | IkFastFuncGetIntPtr = int *(*)() |
using | IkFastFuncComputeIk = bool(*)(const IkReal *targetTranspose, const IkReal *targetRotation, const IkReal *freeParams, ikfast::IkSolutionListBase< IkReal > &solutions) |
using | IkFastFuncComputeFk = void(*)(const IkReal *parameters, IkReal *targetTranspose, IkReal *targetRotation) |
using | IkFastFuncGetConstCharPtr = const char *(*)() |
Protected Member Functions | |
int | getNumFreeParameters () const override |
Returns the number of free parameters users has to set apriori. | |
int * | getFreeParameters () const override |
Returns the indicies of the free parameters indexed by the chain joints. | |
int | getNumJoints () const override |
Returns the total number of indices of the chane. | |
int | getIkRealSize () const override |
Returns the size in bytes of the configured number type. | |
int | getIkType () const override |
Returns the IK type. | |
bool | computeIk (const IkReal *targetTranspose, const IkReal *targetRotation, const IkReal *freeParams, ikfast::IkSolutionListBase< IkReal > &solutions) override |
Computes the inverse kinematics solutions using the generated IKFast code. | |
void | computeFk (const IkReal *parameters, IkReal *targetTranspose, IkReal *targetRotation) override |
Computes the forward kinematics solutions using the generated IKFast code. | |
const char * | getKinematicsHash () override |
Returns a hash of all the chain values used for double checking that the correct IK is used. More... | |
const char * | getIkFastVersion () override |
Returns the IkFast version used to generate this file. | |
void | configure () const override |
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. | |
void | removeObserver (Observer *_observer) const |
Remove an Observer from the list of Observers. | |
Protected Attributes | |
std::string | mFilePath |
File path to the ikfast shared library. | |
std::shared_ptr< common::SharedLibrary > | mSharedLibrary |
IkFastFuncGetInt | mGetNumFreeParameters |
IkFastFuncGetIntPtr | mGetFreeParameters |
IkFastFuncGetInt | mGetNumJoints |
IkFastFuncGetInt | mGetIkRealSize |
IkFastFuncGetInt | mGetIkType |
IkFastFuncComputeIk | mComputeIk |
IkFastFuncComputeFk | mComputeFk |
IkFastFuncGetConstCharPtr | mGetKinematicsHash |
IkFastFuncGetConstCharPtr | mGetIkFastVersion |
![]() | |
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... | |
![]() | |
std::vector< Solution > | mSolutions |
Vector of solutions. | |
UniqueProperties | mAnalyticalP |
Properties for this Analytical IK solver. | |
![]() | |
common::sub_ptr< InverseKinematics > | mIK |
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. | |
![]() | |
std::set< Observer * > | mObservers |
List of current Observers. | |
Additional Inherited Members | |
![]() | |
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... | |
![]() | |
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 |
IkFast-based analytical inverse kinematics class.
The detail of IkFast can be found here: http://openrave.org/docs/0.8.2/openravepy/ikfast/
dart::dynamics::SharedLibraryIkFast::SharedLibraryIkFast | ( | InverseKinematics * | ik, |
const std::string & | filePath, | ||
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] | filePath | The path to the shared library of the IkFast binary file |
[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. |
|
overrideprotectedvirtual |
Configure IkFast.
If it's successfully configured, isConfigured() returns true.
Reimplemented from dart::dynamics::IkFast.
|
overrideprotectedvirtual |
Returns a hash of all the chain values used for double checking that the correct IK is used.
Implements dart::dynamics::IkFast.