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

#include <IKNLP.h>

Inheritance diagram for ct::rbd::IKNLP< KINEMATICS, SCALAR >:
ct::optcon::tpl::Nlp< SCALAR >

Public Types

using Scalar_t = SCALAR
 
using Kinematics_t = KINEMATICS
 
using InverseKinematicsBase = ct::rbd::InverseKinematicsBase< KINEMATICS::NJOINTS, SCALAR >
 
using JointPosition_t = typename InverseKinematicsBase::JointPosition_t
 
using JointPositionsVector_t = typename InverseKinematicsBase::JointPositionsVector_t
 
using RigidBodyPoseTpl = typename InverseKinematicsBase::RigidBodyPoseTpl
 
- Public Types inherited from ct::optcon::tpl::Nlp< SCALAR >
typedef Eigen::Matrix< SCALAR, Eigen::Dynamic, 1 > VectorXs
 
typedef Eigen::Matrix< int, Eigen::Dynamic, 1 > VectorXi
 
typedef Eigen::Map< VectorXsMapVecXs
 
typedef Eigen::Map< VectorXiMapVecXi
 
typedef Eigen::Map< const VectorXsMapConstVecXs
 

Public Member Functions

 IKNLP (std::shared_ptr< ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >> costEvaluator, const JointPosition_t &lowerBound, const JointPosition_t &upperBound)
 constructor More...
 
 ~IKNLP () override=default
 
void updateProblem () override
 
JointPosition_t getSolution ()
 
void printSolution () const
 print the solution to command line More...
 
void setInitialGuess (const JointPosition_t &q_init)
 
std::shared_ptr< ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR > > getIKCostEvaluator ()
 
std::shared_ptr< ct::rbd::IKConstraintsContainer< KINEMATICS, SCALAR > > getIKConstraintContainer ()
 
- Public Member Functions inherited from ct::optcon::tpl::Nlp< SCALAR >
 Nlp ()=default
 
virtual ~Nlp ()=default
 
SCALAR evaluateCostFun ()
 
void evaluateCostGradient (const size_t n, MapVecXs &grad)
 
void evaluateConstraints (MapVecXs &values)
 
void evaluateConstraintJacobian (const int nele_jac, MapVecXs &jac)
 
void evaluateHessian (const int nele_hes, MapVecXs &hes, const SCALAR obj_fac, MapConstVecXs &lambda)
 
void getSparsityPatternJacobian (const int nele_jac, MapVecXi &iRow, MapVecXi &jCol) const
 
void getSparsityPatternHessian (const int nele_hes, MapVecXi &iRow, MapVecXi &jCol) const
 
size_t getConstraintsCount () const
 
size_t getNonZeroJacobianCount () const
 
size_t getNonZeroHessianCount ()
 
void getConstraintBounds (MapVecXs &lowerBound, MapVecXs &upperBound, const size_t m) const
 
size_t getVarCount () const
 
void getVariableBounds (MapVecXs &lowerBound, MapVecXs &upperBound, const size_t n) const
 
void extractOptimizationVars (const MapConstVecXs &x, bool isNew)
 
void getInitialGuess (const size_t n, MapVecXs &x) const
 
void getOptimizationMultState (const size_t n, MapVecXs &xMul, MapVecXi &xState) const
 
void getConstraintsMultState (const size_t m, MapVecXs &zMul, MapVecXi &zState) const
 
void getBoundMultipliers (size_t n, MapVecXs &zLow, MapVecXs &zUp) const
 
void getLambdaVars (size_t m, MapVecXs &lambda) const
 
void extractIpoptSolution (const MapConstVecXs &x, const MapConstVecXs &zL, const MapConstVecXs &zU, const MapConstVecXs &lambda)
 
void extractSnoptSolution (const MapVecXs &x, const MapVecXs &xMul, const MapVecXi &xState, const MapVecXs &fMul, const MapVecXi &fState)
 

Additional Inherited Members

- Protected Attributes inherited from ct::optcon::tpl::Nlp< SCALAR >
std::shared_ptr< DiscreteCostEvaluatorBase< SCALAR > > costEvaluator_
 
std::shared_ptr< OptVector< SCALAR > > optVariables_
 
std::shared_ptr< DiscreteConstraintContainerBase< SCALAR > > constraints_
 
Eigen::VectorXi iRowHessianCost_
 
Eigen::VectorXi iRowHessianConstraints_
 
Eigen::VectorXi jColHessianCost_
 
Eigen::VectorXi jColHessianConstraints_
 
Eigen::VectorXi iRowHessian_
 
Eigen::VectorXi jColHessian_
 

Member Typedef Documentation

◆ Scalar_t

template<typename KINEMATICS , typename SCALAR = double>
using ct::rbd::IKNLP< KINEMATICS, SCALAR >::Scalar_t = SCALAR

◆ Kinematics_t

template<typename KINEMATICS , typename SCALAR = double>
using ct::rbd::IKNLP< KINEMATICS, SCALAR >::Kinematics_t = KINEMATICS

◆ InverseKinematicsBase

template<typename KINEMATICS , typename SCALAR = double>
using ct::rbd::IKNLP< KINEMATICS, SCALAR >::InverseKinematicsBase = ct::rbd::InverseKinematicsBase<KINEMATICS::NJOINTS, SCALAR>

◆ JointPosition_t

template<typename KINEMATICS , typename SCALAR = double>
using ct::rbd::IKNLP< KINEMATICS, SCALAR >::JointPosition_t = typename InverseKinematicsBase::JointPosition_t

◆ JointPositionsVector_t

template<typename KINEMATICS , typename SCALAR = double>
using ct::rbd::IKNLP< KINEMATICS, SCALAR >::JointPositionsVector_t = typename InverseKinematicsBase::JointPositionsVector_t

◆ RigidBodyPoseTpl

template<typename KINEMATICS , typename SCALAR = double>
using ct::rbd::IKNLP< KINEMATICS, SCALAR >::RigidBodyPoseTpl = typename InverseKinematicsBase::RigidBodyPoseTpl

Constructor & Destructor Documentation

◆ IKNLP()

template<typename KINEMATICS , typename SCALAR = double>
ct::rbd::IKNLP< KINEMATICS, SCALAR >::IKNLP ( std::shared_ptr< ct::rbd::IKCostEvaluator< KINEMATICS, SCALAR >>  costEvaluator,
const JointPosition_t lowerBound,
const JointPosition_t upperBound 
)
inline

◆ ~IKNLP()

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

Member Function Documentation

◆ updateProblem()

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKNLP< KINEMATICS, SCALAR >::updateProblem ( )
inlineoverridevirtual

◆ getSolution()

template<typename KINEMATICS , typename SCALAR = double>
JointPosition_t ct::rbd::IKNLP< KINEMATICS, SCALAR >::getSolution ( )
inline

◆ printSolution()

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKNLP< KINEMATICS, SCALAR >::printSolution ( ) const
inline

print the solution to command line

References ct::optcon::tpl::Nlp< SCALAR >::optVariables_.

◆ setInitialGuess()

template<typename KINEMATICS , typename SCALAR = double>
void ct::rbd::IKNLP< KINEMATICS, SCALAR >::setInitialGuess ( const JointPosition_t q_init)
inline

◆ getIKCostEvaluator()

template<typename KINEMATICS , typename SCALAR = double>
std::shared_ptr<ct::rbd::IKCostEvaluator<KINEMATICS, SCALAR> > ct::rbd::IKNLP< KINEMATICS, SCALAR >::getIKCostEvaluator ( )
inline

◆ getIKConstraintContainer()

template<typename KINEMATICS , typename SCALAR = double>
std::shared_ptr<ct::rbd::IKConstraintsContainer<KINEMATICS, SCALAR> > ct::rbd::IKNLP< KINEMATICS, SCALAR >::getIKConstraintContainer ( )
inline

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