- 3.0.2 models module.
ct::rbd::HyAInverseKinematics< SCALAR > Class Template Reference

#include <HyAInverseKinematics.h>

Inheritance diagram for ct::rbd::HyAInverseKinematics< SCALAR >:
ct::rbd::InverseKinematicsBase< 6, SCALAR >

Public Types

using BASE = InverseKinematicsBase< 6, SCALAR >
 
using JointPosition_t = typename BASE::JointPosition_t
 
using JointPositionsVector_t = typename BASE::JointPositionsVector_t
 
using RigidBodyPoseTpl = typename BASE::RigidBodyPoseTpl
 
- Public Types inherited from ct::rbd::InverseKinematicsBase< 6, SCALAR >
typedef typename JointState< 6, SCALAR >::Position JointPosition_t
 
typedef std::vector< JointPosition_t, Eigen::aligned_allocator< JointPosition_t > > JointPositionsVector_t
 
typedef tpl::RigidBodyPose< SCALARRigidBodyPoseTpl
 

Public Member Functions

 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
 
- Public Member Functions inherited from ct::rbd::InverseKinematicsBase< 6, SCALAR >
 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 InverseKinematicsSettingsgetSettings () const
 
void updateSettings (const InverseKinematicsSettings &settings)
 

Additional Inherited Members

- Protected Attributes inherited from ct::rbd::InverseKinematicsBase< 6, SCALAR >
InverseKinematicsSettings settings_
 

Member Typedef Documentation

◆ BASE

template<typename SCALAR = double>
using ct::rbd::HyAInverseKinematics< SCALAR >::BASE = InverseKinematicsBase<6, SCALAR>

◆ JointPosition_t

template<typename SCALAR = double>
using ct::rbd::HyAInverseKinematics< SCALAR >::JointPosition_t = typename BASE::JointPosition_t

◆ JointPositionsVector_t

template<typename SCALAR = double>
using ct::rbd::HyAInverseKinematics< SCALAR >::JointPositionsVector_t = typename BASE::JointPositionsVector_t

◆ RigidBodyPoseTpl

template<typename SCALAR = double>
using ct::rbd::HyAInverseKinematics< SCALAR >::RigidBodyPoseTpl = typename BASE::RigidBodyPoseTpl

Constructor & Destructor Documentation

◆ HyAInverseKinematics()

template<typename SCALAR = double>
ct::rbd::HyAInverseKinematics< SCALAR >::HyAInverseKinematics ( )
default

◆ ~HyAInverseKinematics()

template<typename SCALAR = double>
ct::rbd::HyAInverseKinematics< SCALAR >::~HyAInverseKinematics ( )
default

Member Function Documentation

◆ computeInverseKinematics() [1/2]

◆ computeInverseKinematics() [2/2]

template<typename SCALAR = double>
bool ct::rbd::HyAInverseKinematics< SCALAR >::computeInverseKinematics ( JointPositionsVector_t res,
const RigidBodyPoseTpl eeWorldPose,
const RigidBodyPoseTpl baseWorldPose,
const std::vector< size_t > &  freeJoints = std::vector<size_t>() 
)
inlineoverride

The documentation for this class was generated from the following file: