|
| HuboArmIK (InverseKinematics *_ik, const std::string &baseLinkName, const Analytical::Properties &properties=Analytical::Properties()) |
|
std::unique_ptr< GradientMethod > | clone (InverseKinematics *_newIK) const override |
| Enable this GradientMethod to be cloned to a new IK module.
|
|
const std::vector< Solution > & | computeSolutions (const Eigen::Isometry3d &_desiredBodyTf) override |
| Use this function to fill the entries of the mSolutions variable. More...
|
|
const std::vector< std::size_t > & | getDofs () const override |
| Get a list of the DOFs that will be included in the entries of the solutions returned by getSolutions(). More...
|
|
| 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.
|
|
The HuboArmIK is based on the derivation of Hubo's arm IK by Matt Zucker.