- 3.0.2 rigid body dynamics module.
ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR > Class Template Referenceabstract

#include <InverseKinematicsBase.h>

Public Types

using JointPosition_t = typename JointState< NJOINTS, SCALAR >::Position
 
using JointPositionsVector_t = std::vector< JointPosition_t, Eigen::aligned_allocator< JointPosition_t > >
 
using RigidBodyPoseTpl = tpl::RigidBodyPose< SCALAR >
 

Public Member Functions

 InverseKinematicsBase ()=default
 default constructor More...
 
 InverseKinematicsBase (const InverseKinematicsSettings &settings)
 constructor with additional settings More...
 
virtual ~InverseKinematicsBase ()=default
 default destructor More...
 
virtual bool computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &eeBasePose, const std::vector< size_t > &freeJoints)=0
 compute inverse kinematics for an end-effector w.r.t robot base More...
 
virtual bool computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const std::vector< size_t > &freeJoints)=0
 compute inverse kinematics for an end-effector More...
 
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 >())
 compute inverse kinematics for an end-effector More...
 
virtual bool computeInverseKinematicsCloseTo (JointPosition_t &ikSolution, const RigidBodyPoseTpl &eeBasePose, const JointPosition_t &queryJointPositions, const std::vector< size_t > &freeJoints=std::vector< size_t >())
 compute inverse kinematics for an end-effector More...
 
const InverseKinematicsSettingsgetSettings () const
 
void updateSettings (const InverseKinematicsSettings &settings)
 

Protected Attributes

InverseKinematicsSettings settings_
 

Member Typedef Documentation

◆ JointPosition_t

template<size_t NJOINTS, typename SCALAR = double>
using ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::JointPosition_t = typename JointState<NJOINTS, SCALAR>::Position

◆ JointPositionsVector_t

template<size_t NJOINTS, typename SCALAR = double>
using ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::JointPositionsVector_t = std::vector<JointPosition_t, Eigen::aligned_allocator<JointPosition_t> >

◆ RigidBodyPoseTpl

template<size_t NJOINTS, typename SCALAR = double>
using ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::RigidBodyPoseTpl = tpl::RigidBodyPose<SCALAR>

Constructor & Destructor Documentation

◆ InverseKinematicsBase() [1/2]

template<size_t NJOINTS, typename SCALAR = double>
ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::InverseKinematicsBase ( )
default

default constructor

◆ InverseKinematicsBase() [2/2]

template<size_t NJOINTS, typename SCALAR = double>
ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::InverseKinematicsBase ( const InverseKinematicsSettings settings)
inline

constructor with additional settings

◆ ~InverseKinematicsBase()

template<size_t NJOINTS, typename SCALAR = double>
virtual ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::~InverseKinematicsBase ( )
virtualdefault

default destructor

Member Function Documentation

◆ computeInverseKinematics() [1/2]

template<size_t NJOINTS, typename SCALAR = double>
virtual bool ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::computeInverseKinematics ( JointPositionsVector_t ikSolutions,
const RigidBodyPoseTpl eeBasePose,
const std::vector< size_t > &  freeJoints 
)
pure virtual

compute inverse kinematics for an end-effector w.r.t robot base

Parameters
ikSolutionsvector of all solutions to the inverse kinematics problem
eeBasePoseend-effector pose in base coordinates
freeJointsvector of indices of the free joints
Returns
true if solution found, false otherwise

◆ computeInverseKinematics() [2/2]

template<size_t NJOINTS, typename SCALAR = double>
virtual bool ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::computeInverseKinematics ( JointPositionsVector_t ikSolutions,
const RigidBodyPoseTpl eeWorldPose,
const RigidBodyPoseTpl baseWorldPose,
const std::vector< size_t > &  freeJoints 
)
pure virtual

compute inverse kinematics for an end-effector

Parameters
ikSolutionsvector of all solutions to the inverse kinematics problem
eeWorldPoseend-effector pose in world coordinates
baseWorldPosebase pose in world coordinates
freeJointsvector of indices of the free joints
Returns
true if solution found, false otherwise

◆ computeInverseKinematicsCloseTo() [1/2]

template<size_t NJOINTS, typename SCALAR = double>
virtual bool ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::computeInverseKinematicsCloseTo ( JointPosition_t ikSolution,
const RigidBodyPoseTpl eeWorldPose,
const RigidBodyPoseTpl baseWorldPose,
const JointPosition_t queryJointPositions,
const std::vector< size_t > &  freeJoints = std::vector<size_t>() 
)
inlinevirtual

compute inverse kinematics for an end-effector

Parameters
ikSolutionsolution to the inverse kinematics problem which is closest to parameter 'queryJointPositions'
eeWorldPoseend-effector pose in world coordinates
baseWorldPosebase pose in world coordinates
freeJointsvector of indices of the free joints
Returns
true if solution found, false otherwise

◆ computeInverseKinematicsCloseTo() [2/2]

template<size_t NJOINTS, typename SCALAR = double>
virtual bool ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::computeInverseKinematicsCloseTo ( JointPosition_t ikSolution,
const RigidBodyPoseTpl eeBasePose,
const JointPosition_t queryJointPositions,
const std::vector< size_t > &  freeJoints = std::vector<size_t>() 
)
inlinevirtual

compute inverse kinematics for an end-effector

Parameters
ikSolutionsolution to the inverse kinematics problem which is closest to parameter 'queryJointPositions'
eeBasePoseend-effector pose in base coordinates
freeJointsvector of indices of the free joints
Returns
true if solution found, false otherwise

◆ getSettings()

template<size_t NJOINTS, typename SCALAR = double>
const InverseKinematicsSettings& ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::getSettings ( ) const
inline

◆ updateSettings()

template<size_t NJOINTS, typename SCALAR = double>
void ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::updateSettings ( const InverseKinematicsSettings settings)
inline

Member Data Documentation

◆ settings_

template<size_t NJOINTS, typename SCALAR = double>
InverseKinematicsSettings ct::rbd::InverseKinematicsBase< NJOINTS, SCALAR >::settings_
protected

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