- 3.0.2 rigid body dynamics module.
ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics > Class Template Reference

#include <InfiniteHorizonLQRwithInverseDynamics.h>

Inheritance diagram for ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >:
ct::core::Controller< RBDDynamics::NSTATE, RBDDynamics::NJOINTS >

Public Types

typedef RBDDynamics::SCALAR SCALAR
 
typedef RBDDynamics::control_vector_t control_vector_t
 
typedef RBDDynamics::state_vector_t state_vector_t
 
typedef RBDDynamics::JointAcceleration_t JointAcceleration_t
 
typedef core::StateMatrix< RBDDynamics::NSTATE, SCALARstate_matrix_t
 
typedef core::StateMatrix< RBDDynamics::NJOINTS, SCALARcontrol_matrix_t
 
typedef core::StateControlMatrix< RBDDynamics::NSTATE, RBDDynamics::NJOINTS, SCALARstate_control_matrix_t
 
typedef core::FeedbackMatrix< RBDDynamics::NSTATE, RBDDynamics::NJOINTS, SCALARfeedback_matrix_t
 

Public Member Functions

 InfiniteHorizonLQRwithInverseDynamics ()
 
 InfiniteHorizonLQRwithInverseDynamics (std::shared_ptr< ct::rbd::FixBaseFDSystem< RBDDynamics >> system, std::shared_ptr< ct::core::LinearSystem< 2 *(RBDDynamics::NJOINTS), RBDDynamics::NJOINTS >> linearSystem)
 
 InfiniteHorizonLQRwithInverseDynamics (const InfiniteHorizonLQRwithInverseDynamics &arg)
 
virtual ~InfiniteHorizonLQRwithInverseDynamics ()
 
virtual InfiniteHorizonLQRwithInverseDynamicsclone () const override
 
virtual void computeControl (const ct::core::StateVector< RBDDynamics::NSTATE, SCALAR > &state, const ct::core::Time &t, ct::core::ControlVector< RBDDynamics::NJOINTS, SCALAR > &controlAction) override
 
const feedback_matrix_tgetK ()
 
bool designInfiniteHorizonLQR (const state_vector_t &stateSetpoint, const state_matrix_t &Q_stab, const control_matrix_t &R_stab, feedback_matrix_t &K)
 
bool designInfiniteHorizonLQR (const state_vector_t &stateSetpoint, const state_matrix_t &Q_stab, const control_matrix_t &R_stab)
 
const control_vector_tgetIDTorques () const
 
const state_vector_tgetStateSetpoint () const
 
void setNonlinearSystem (std::shared_ptr< ct::rbd::FixBaseFDSystem< RBDDynamics >> system)
 
void setLinearSystem (std::shared_ptr< ct::core::LinearSystem< 2 *(RBDDynamics::NJOINTS), RBDDynamics::NJOINTS >> system)
 
- Public Member Functions inherited from ct::core::Controller< RBDDynamics::NSTATE, RBDDynamics::NJOINTS >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Controller ()
 
 Controller (const Controller &other)
 
virtual ~Controller ()
 
virtual void computeControl (const StateVector< RBDDynamics::NSTATE, SCALAR > &state, const SCALAR &t, ControlVector< RBDDynamics::NJOINTS, SCALAR > &controlAction)=0
 
virtual ControlMatrix< RBDDynamics::NJOINTS, SCALARgetDerivativeU0 (const StateVector< RBDDynamics::NSTATE, SCALAR > &state, const SCALAR time)
 
virtual ControlMatrix< RBDDynamics::NJOINTS, SCALARgetDerivativeUf (const StateVector< RBDDynamics::NSTATE, SCALAR > &state, const SCALAR time)
 

Member Typedef Documentation

◆ SCALAR

template<class RBDDynamics>
typedef RBDDynamics::SCALAR ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::SCALAR

◆ control_vector_t

template<class RBDDynamics>
typedef RBDDynamics::control_vector_t ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::control_vector_t

◆ state_vector_t

template<class RBDDynamics>
typedef RBDDynamics::state_vector_t ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::state_vector_t

◆ JointAcceleration_t

template<class RBDDynamics>
typedef RBDDynamics::JointAcceleration_t ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::JointAcceleration_t

◆ state_matrix_t

template<class RBDDynamics>
typedef core::StateMatrix<RBDDynamics::NSTATE, SCALAR> ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::state_matrix_t

◆ control_matrix_t

template<class RBDDynamics>
typedef core::StateMatrix<RBDDynamics::NJOINTS, SCALAR> ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::control_matrix_t

◆ state_control_matrix_t

template<class RBDDynamics>
typedef core::StateControlMatrix<RBDDynamics::NSTATE, RBDDynamics::NJOINTS, SCALAR> ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::state_control_matrix_t

◆ feedback_matrix_t

template<class RBDDynamics>
typedef core::FeedbackMatrix<RBDDynamics::NSTATE, RBDDynamics::NJOINTS, SCALAR> ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::feedback_matrix_t

Constructor & Destructor Documentation

◆ InfiniteHorizonLQRwithInverseDynamics() [1/3]

template<class RBDDynamics>
ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::InfiniteHorizonLQRwithInverseDynamics ( )
inline

◆ InfiniteHorizonLQRwithInverseDynamics() [2/3]

template<class RBDDynamics>
ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::InfiniteHorizonLQRwithInverseDynamics ( std::shared_ptr< ct::rbd::FixBaseFDSystem< RBDDynamics >>  system,
std::shared_ptr< ct::core::LinearSystem< 2 *(RBDDynamics::NJOINTS), RBDDynamics::NJOINTS >>  linearSystem 
)
inline

◆ InfiniteHorizonLQRwithInverseDynamics() [3/3]

template<class RBDDynamics>
ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::InfiniteHorizonLQRwithInverseDynamics ( const InfiniteHorizonLQRwithInverseDynamics< RBDDynamics > &  arg)
inline

◆ ~InfiniteHorizonLQRwithInverseDynamics()

template<class RBDDynamics>
virtual ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::~InfiniteHorizonLQRwithInverseDynamics ( )
inlinevirtual

Member Function Documentation

◆ clone()

template<class RBDDynamics>
virtual InfiniteHorizonLQRwithInverseDynamics* ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::clone ( ) const
inlineoverridevirtual

◆ computeControl()

template<class RBDDynamics>
virtual void ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::computeControl ( const ct::core::StateVector< RBDDynamics::NSTATE, SCALAR > &  state,
const ct::core::Time t,
ct::core::ControlVector< RBDDynamics::NJOINTS, SCALAR > &  controlAction 
)
inlineoverridevirtual

◆ getK()

template<class RBDDynamics>
const feedback_matrix_t& ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::getK ( )
inline

◆ designInfiniteHorizonLQR() [1/2]

template<class RBDDynamics>
bool ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::designInfiniteHorizonLQR ( const state_vector_t stateSetpoint,
const state_matrix_t Q_stab,
const control_matrix_t R_stab,
feedback_matrix_t K 
)
inline

◆ designInfiniteHorizonLQR() [2/2]

template<class RBDDynamics>
bool ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::designInfiniteHorizonLQR ( const state_vector_t stateSetpoint,
const state_matrix_t Q_stab,
const control_matrix_t R_stab 
)
inline

◆ getIDTorques()

template<class RBDDynamics>
const control_vector_t& ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::getIDTorques ( ) const
inline

◆ getStateSetpoint()

template<class RBDDynamics>
const state_vector_t& ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::getStateSetpoint ( ) const
inline

◆ setNonlinearSystem()

template<class RBDDynamics>
void ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::setNonlinearSystem ( std::shared_ptr< ct::rbd::FixBaseFDSystem< RBDDynamics >>  system)
inline

◆ setLinearSystem()

template<class RBDDynamics>
void ct::rbd::InfiniteHorizonLQRwithInverseDynamics< RBDDynamics >::setLinearSystem ( std::shared_ptr< ct::core::LinearSystem< 2 *(RBDDynamics::NJOINTS), RBDDynamics::NJOINTS >>  system)
inline

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