#include <HyAInverseKinematics.h>
|
| HyAInverseKinematics ()=default |
|
| ~HyAInverseKinematics ()=default |
|
bool | computeInverseKinematics (JointPositionsVector_t &res, const RigidBodyPoseTpl &eeBasePose, const std::vector< size_t > &freeJoints=std::vector< size_t >()) override |
|
bool | computeInverseKinematics (JointPositionsVector_t &res, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const std::vector< size_t > &freeJoints=std::vector< size_t >()) override |
|
| InverseKinematicsBase ()=default |
|
| InverseKinematicsBase (const InverseKinematicsSettings &settings) |
|
virtual | ~InverseKinematicsBase ()=default |
|
virtual bool | computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &eeBasePose, const std::vector< size_t > &freeJoints)=0 |
|
virtual bool | computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const std::vector< size_t > &freeJoints)=0 |
|
virtual bool | computeInverseKinematicsCloseTo (JointPosition_t &ikSolution, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const JointPosition_t &queryJointPositions, const std::vector< size_t > &freeJoints=std::vector< size_t >()) |
|
virtual bool | computeInverseKinematicsCloseTo (JointPosition_t &ikSolution, const RigidBodyPoseTpl &eeBasePose, const JointPosition_t &queryJointPositions, const std::vector< size_t > &freeJoints=std::vector< size_t >()) |
|
const InverseKinematicsSettings & | getSettings () const |
|
void | updateSettings (const InverseKinematicsSettings &settings) |
|
◆ BASE
template<typename SCALAR = double>
◆ JointPosition_t
template<typename SCALAR = double>
◆ JointPositionsVector_t
template<typename SCALAR = double>
◆ RigidBodyPoseTpl
template<typename SCALAR = double>
◆ HyAInverseKinematics()
template<typename SCALAR = double>
◆ ~HyAInverseKinematics()
template<typename SCALAR = double>
◆ computeInverseKinematics() [1/2]
template<typename SCALAR = double>
References ct::rbd::JointState< NJOINTS, SCALAR >::checkPositionLimits(), ComputeIk(), GetNumFreeParameters(), ikfast::IkSolutionList< class >::GetNumSolutions(), ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), ikfast::IkSolutionList< class >::GetSolution(), ikfast::IkSolutionBase< class >::GetSolution(), i, ct::models::HyA::jointLowerLimit(), ct::models::HyA::jointUpperLimit(), and ct::rbd::JointState< NJOINTS, SCALAR >::toUniquePosition().
Referenced by TEST().
◆ computeInverseKinematics() [2/2]
template<typename SCALAR = double>
The documentation for this class was generated from the following file: