- 3.0.2 rigid body dynamics module.
ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN > Class Template Reference

#include <IKNLPSolverIpopt.h>

Inheritance diagram for ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >:
ct::rbd::InverseKinematicsBase< IKNLP::Kinematics_t::NJOINTS, IKNLP::Scalar_t >

Public Types

using KINEMATICS = typename IKNLP::Kinematics_t
 
using SCALAR = typename IKNLP::Scalar_t
 
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::rbd::InverseKinematicsBase< IKNLP::Kinematics_t::NJOINTS, IKNLP::Scalar_t >
using JointPosition_t = typename JointState< NJOINTS, IKNLP::Scalar_t >::Position
 
using JointPositionsVector_t = std::vector< JointPosition_t, Eigen::aligned_allocator< JointPosition_t > >
 
using RigidBodyPoseTpl = tpl::RigidBodyPose< IKNLP::Scalar_t >
 

Public Member Functions

 IKNLPSolverIpopt ()
 
 IKNLPSolverIpopt (std::shared_ptr< IKNLP > iknlp, ct::optcon::NlpSolverSettings nlpSolverSettings, const size_t eeInd=0)
 constructor More...
 
 IKNLPSolverIpopt (std::shared_ptr< IKNLP > iknlp, ct::optcon::NlpSolverSettings nlpSolverSettings, const ct::rbd::InverseKinematicsSettings &ikSettings, const size_t eeInd=0)
 constructor with additional inverse kinematics settings More...
 
void setInitialGuess (const JointPosition_t &q_init)
 
bool computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &ee_W_base, const std::vector< size_t > &freeJoints=std::vector< size_t >()) override
 
bool computeInverseKinematics (JointPositionsVector_t &ikSolutions, const RigidBodyPoseTpl &eeWorldPose, const RigidBodyPoseTpl &baseWorldPose, const std::vector< size_t > &freeJoints) override
 
- Public Member Functions inherited from ct::rbd::InverseKinematicsBase< IKNLP::Kinematics_t::NJOINTS, IKNLP::Scalar_t >
 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)
 

Additional Inherited Members

- Protected Attributes inherited from ct::rbd::InverseKinematicsBase< IKNLP::Kinematics_t::NJOINTS, IKNLP::Scalar_t >
InverseKinematicsSettings settings_
 

Member Typedef Documentation

◆ KINEMATICS

template<typename IKNLP , typename VALIDATION_KIN >
using ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::KINEMATICS = typename IKNLP::Kinematics_t

◆ SCALAR

template<typename IKNLP , typename VALIDATION_KIN >
using ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::SCALAR = typename IKNLP::Scalar_t

◆ InverseKinematicsBase

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

◆ JointPosition_t

template<typename IKNLP , typename VALIDATION_KIN >
using ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::JointPosition_t = typename InverseKinematicsBase::JointPosition_t

◆ JointPositionsVector_t

template<typename IKNLP , typename VALIDATION_KIN >
using ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::JointPositionsVector_t = typename InverseKinematicsBase::JointPositionsVector_t

◆ RigidBodyPoseTpl

template<typename IKNLP , typename VALIDATION_KIN >
using ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::RigidBodyPoseTpl = typename InverseKinematicsBase::RigidBodyPoseTpl

Constructor & Destructor Documentation

◆ IKNLPSolverIpopt() [1/3]

template<typename IKNLP , typename VALIDATION_KIN >
ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::IKNLPSolverIpopt ( )
inline

◆ IKNLPSolverIpopt() [2/3]

template<typename IKNLP , typename VALIDATION_KIN >
ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::IKNLPSolverIpopt ( std::shared_ptr< IKNLP iknlp,
ct::optcon::NlpSolverSettings  nlpSolverSettings,
const size_t  eeInd = 0 
)
inline

constructor

◆ IKNLPSolverIpopt() [3/3]

template<typename IKNLP , typename VALIDATION_KIN >
ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::IKNLPSolverIpopt ( std::shared_ptr< IKNLP iknlp,
ct::optcon::NlpSolverSettings  nlpSolverSettings,
const ct::rbd::InverseKinematicsSettings ikSettings,
const size_t  eeInd = 0 
)
inline

constructor with additional inverse kinematics settings

Member Function Documentation

◆ setInitialGuess()

template<typename IKNLP , typename VALIDATION_KIN >
void ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::setInitialGuess ( const JointPosition_t q_init)
inline

◆ computeInverseKinematics() [1/2]

template<typename IKNLP , typename VALIDATION_KIN >
bool ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::computeInverseKinematics ( JointPositionsVector_t ikSolutions,
const RigidBodyPoseTpl ee_W_base,
const std::vector< size_t > &  freeJoints = std::vector<size_t>() 
)
inlineoverride

Referenced by TEST().

◆ computeInverseKinematics() [2/2]

template<typename IKNLP , typename VALIDATION_KIN >
bool ct::rbd::IKNLPSolverIpopt< IKNLP, VALIDATION_KIN >::computeInverseKinematics ( JointPositionsVector_t ikSolutions,
const RigidBodyPoseTpl eeWorldPose,
const RigidBodyPoseTpl baseWorldPose,
const std::vector< size_t > &  freeJoints 
)
inlineoverride

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