- 3.0.2 rigid body dynamics module.
ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR > Class Template Referencefinal

Inverse Kinematics cost evaluator for NLP. More...

#include <IKCostEvaluator.h>

Inheritance diagram for ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >:
ct::optcon::tpl::DiscreteCostEvaluatorBase< SCALAR >

Public Member Functions

 IKCostEvaluator (size_t eeInd, const Eigen::Matrix3d &Qpos=Eigen::Matrix3d::Identity(), const Eigen::Matrix3d &Qrot=Eigen::Matrix3d::Identity())
 
 IKCostEvaluator (const std::string &costFunctionPath, const std::string &termTaskspaceName, const bool verbose=false)
 
 IKCostEvaluator (const std::string &costFunctionPath, const std::string &termTaskspaceName, const std::string &termJointPosName, const bool verbose=false)
 
 ~IKCostEvaluator () override=default
 
void setOptVector (std::shared_ptr< ct::optcon::tpl::OptVector< SCALAR >> optVector)
 opt vector needs to be set by NLP solver More...
 
void setRegularizer (std::shared_ptr< IKRegularizerBase > reg)
 
ct::rbd::RigidBodyPose getTargetPose ()
 
void setTargetPose (const ct::rbd::RigidBodyPose &rbdPose)
 
void setTargetPose (const core::StateVector< 3 > &w_pos_des, const Eigen::Quaterniond &w_q_des)
 
void setTargetPose (const core::StateVector< 3 > &w_pos_des, const Eigen::Matrix3d &eulerXyz)
 
virtual SCALAR eval () override
 evaluate cost function More...
 
virtual void evalGradient (size_t grad_length, Eigen::Map< Eigen::Matrix< SCALAR, Eigen::Dynamic, 1 >> &grad) override
 retrieve first-order derivative More...
 
virtual void getSparsityPatternHessian (Eigen::VectorXi &iRow, Eigen::VectorXi &jCol) override
 create sparsity pattern for the hessian (simply fill up completely) More...
 
void sparseHessianValues (const Eigen::VectorXd &jointAngles, const Eigen::VectorXd &obj_fac, Eigen::VectorXd &hes) override
 retrieve second order derivative More...
 
- Public Member Functions inherited from ct::optcon::tpl::DiscreteCostEvaluatorBase< SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW DiscreteCostEvaluatorBase ()=default
 
virtual ~DiscreteCostEvaluatorBase ()=default
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t NJOINTS = KINEMATICS::NJOINTS
 

Detailed Description

template<typename KINEMATICS, typename SCALAR = double>
class ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >

Inverse Kinematics cost evaluator for NLP.

Warning
currently this works only with fix-base systems

Constructor & Destructor Documentation

◆ IKCostEvaluator() [1/3]

template<typename KINEMATICS , typename SCALAR = double>
ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::IKCostEvaluator ( size_t  eeInd,
const Eigen::Matrix3d &  Qpos = Eigen::Matrix3d::Identity(),
const Eigen::Matrix3d &  Qrot = Eigen::Matrix3d::Identity() 
)
inline

◆ IKCostEvaluator() [2/3]

template<typename KINEMATICS , typename SCALAR = double>
ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::IKCostEvaluator ( const std::string &  costFunctionPath,
const std::string &  termTaskspaceName,
const bool  verbose = false 
)
inline

◆ IKCostEvaluator() [3/3]

template<typename KINEMATICS , typename SCALAR = double>
ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::IKCostEvaluator ( const std::string &  costFunctionPath,
const std::string &  termTaskspaceName,
const std::string &  termJointPosName,
const bool  verbose = false 
)
inline

◆ ~IKCostEvaluator()

template<typename KINEMATICS , typename SCALAR = double>
ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::~IKCostEvaluator ( )
overridedefault

Member Function Documentation

◆ setOptVector()

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::setOptVector ( std::shared_ptr< ct::optcon::tpl::OptVector< SCALAR >>  optVector)
inline

opt vector needs to be set by NLP solver

◆ setRegularizer()

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::setRegularizer ( std::shared_ptr< IKRegularizerBase reg)
inline

◆ getTargetPose()

template<typename KINEMATICS , typename SCALAR = double>
ct::rbd::RigidBodyPose ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::getTargetPose ( )
inline

◆ setTargetPose() [1/3]

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::setTargetPose ( const ct::rbd::RigidBodyPose rbdPose)
inline

◆ setTargetPose() [2/3]

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::setTargetPose ( const core::StateVector< 3 > &  w_pos_des,
const Eigen::Quaterniond &  w_q_des 
)
inline

◆ setTargetPose() [3/3]

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::setTargetPose ( const core::StateVector< 3 > &  w_pos_des,
const Eigen::Matrix3d &  eulerXyz 
)
inline

◆ eval()

template<typename KINEMATICS , typename SCALAR = double>
virtual SCALAR ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::eval ( )
inlineoverridevirtual

evaluate cost function

Implements ct::optcon::tpl::DiscreteCostEvaluatorBase< SCALAR >.

◆ evalGradient()

template<typename KINEMATICS , typename SCALAR = double>
virtual void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::evalGradient ( size_t  grad_length,
Eigen::Map< Eigen::Matrix< SCALAR, Eigen::Dynamic, 1 >> &  grad 
)
inlineoverridevirtual

retrieve first-order derivative

Implements ct::optcon::tpl::DiscreteCostEvaluatorBase< SCALAR >.

◆ getSparsityPatternHessian()

template<typename KINEMATICS , typename SCALAR = double>
virtual void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::getSparsityPatternHessian ( Eigen::VectorXi &  iRow,
Eigen::VectorXi &  jCol 
)
inlineoverridevirtual

create sparsity pattern for the hessian (simply fill up completely)

Reimplemented from ct::optcon::tpl::DiscreteCostEvaluatorBase< SCALAR >.

References i, and ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::NJOINTS.

◆ sparseHessianValues()

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::sparseHessianValues ( const Eigen::VectorXd &  jointAngles,
const Eigen::VectorXd &  obj_fac,
Eigen::VectorXd &  hes 
)
inlineoverridevirtual

Member Data Documentation

◆ NJOINTS

template<typename KINEMATICS , typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >::NJOINTS = KINEMATICS::NJOINTS
static

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