- 3.0.2 models module.
ct::models::HyQ::HyQWithContactModelLinearizedReverse Class Reference

#include <HyQWithContactModelLinearizedReverse.h>

Inheritance diagram for ct::models::HyQ::HyQWithContactModelLinearizedReverse:
ct::core::LinearSystem< 36, 12 > ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > ct::core::System< STATE_DIM, SCALAR >

Public Types

typedef ct::core::StateMatrix< 36, double > state_matrix_t
 
typedef ct::core::StateControlMatrix< 36, 12, double > state_control_matrix_t
 
- Public Types inherited from ct::core::LinearSystem< 36, 12 >
typedef Base::time_t time_t
 
typedef StateVector< 36, SCALARstate_vector_t
 
typedef ControlVector< 12, SCALARcontrol_vector_t
 
typedef StateMatrix< 36, SCALARstate_matrix_t
 
typedef StateControlMatrix< 36, 12, SCALARstate_control_matrix_t
 
- Public Types inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
typedef std::shared_ptr< ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR > > Ptr
 
typedef Base::time_t time_t
 
- Public Types inherited from ct::core::System< STATE_DIM, SCALAR >
typedef SCALAR time_t
 

Public Member Functions

 HyQWithContactModelLinearizedReverse (const ct::core::SYSTEM_TYPE &type=ct::core::SYSTEM_TYPE::GENERAL)
 
 HyQWithContactModelLinearizedReverse (const HyQWithContactModelLinearizedReverse &other)
 
virtual ~HyQWithContactModelLinearizedReverse ()
 
virtual HyQWithContactModelLinearizedReverseclone () const override
 
virtual const state_matrix_tgetDerivativeState (const ct::core::StateVector< 36 > &x, const ct::core::ControlVector< 12 > &u, const double t=0.0) override
 
virtual const state_control_matrix_tgetDerivativeControl (const ct::core::StateVector< 36 > &x, const ct::core::ControlVector< 12 > &u, const double t=0.0) override
 
- Public Member Functions inherited from ct::core::LinearSystem< 36, 12 >
 LinearSystem (const ct::core::SYSTEM_TYPE &type=ct::core::SYSTEM_TYPE::GENERAL)
 
virtual ~LinearSystem ()
 
virtual void computeControlledDynamics (const state_vector_t &state, const time_t &t, const control_vector_t &control, state_vector_t &derivative) override
 
virtual const state_matrix_tgetDerivativeState (const state_vector_t &x, const control_vector_t &u, const time_t t=time_t(0.0))=0
 
virtual const state_control_matrix_tgetDerivativeControl (const state_vector_t &x, const control_vector_t &u, const time_t t=time_t(0.0))=0
 
virtual void getDerivatives (state_matrix_t &A, state_control_matrix_t &B, const state_vector_t &x, const control_vector_t &u, const time_t t=time_t(0.0))
 
- Public Member Functions inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
 ControlledSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (std::shared_ptr< ct::core::Controller< STATE_DIM, CONTROL_DIM, SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (const ControlledSystem &arg)
 
virtual ~ControlledSystem ()
 
void setController (const std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &controller)
 
void getController (std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR >> &controller) const
 
std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR > > getController ()
 
virtual void computeDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, StateVector< STATE_DIM, SCALAR > &derivative) override
 
virtual void computeControlledDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, const ControlVector< CONTROL_DIM, SCALAR > &control, StateVector< STATE_DIM, SCALAR > &derivative)=0
 
ControlVector< CONTROL_DIM, SCALARgetLastControlAction ()
 
- Public Member Functions inherited from ct::core::System< STATE_DIM, SCALAR >
 System (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 System (const System &other)
 
virtual ~System ()
 
virtual void computeDynamics (const StateVector< STATE_DIM, SCALAR > &state, const time_t &t, StateVector< STATE_DIM, SCALAR > &derivative)=0
 
SYSTEM_TYPE getType () const
 
virtual bool isSymplectic () const
 

Additional Inherited Members

- Public Attributes inherited from ct::core::LinearSystem< 36, 12 >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ControlledSystem< 36, 12, SCALARBase
 
- Public Attributes inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System< STATE_DIM, SCALARBase
 
- Public Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SCALAR S
 
- Protected Attributes inherited from ct::core::ControlledSystem< STATE_DIM, CONTROL_DIM, SCALAR >
std::shared_ptr< Controller< STATE_DIM, CONTROL_DIM, SCALAR > > controller_
 
ControlVector< CONTROL_DIM, SCALARcontrolAction_
 
- Protected Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
SYSTEM_TYPE type_
 

Member Typedef Documentation

◆ state_matrix_t

◆ state_control_matrix_t

Constructor & Destructor Documentation

◆ HyQWithContactModelLinearizedReverse() [1/2]

ct::models::HyQ::HyQWithContactModelLinearizedReverse::HyQWithContactModelLinearizedReverse ( const ct::core::SYSTEM_TYPE type = ct::core::SYSTEM_TYPE::GENERAL)
inline

Referenced by clone().

◆ HyQWithContactModelLinearizedReverse() [2/2]

ct::models::HyQ::HyQWithContactModelLinearizedReverse::HyQWithContactModelLinearizedReverse ( const HyQWithContactModelLinearizedReverse other)
inline

◆ ~HyQWithContactModelLinearizedReverse()

virtual ct::models::HyQ::HyQWithContactModelLinearizedReverse::~HyQWithContactModelLinearizedReverse ( )
inlinevirtual

Member Function Documentation

◆ clone()

virtual HyQWithContactModelLinearizedReverse* ct::models::HyQ::HyQWithContactModelLinearizedReverse::clone ( ) const
inlineoverridevirtual

◆ getDerivativeState()

const HyQWithContactModelLinearizedReverse::state_matrix_t & ct::models::HyQ::HyQWithContactModelLinearizedReverse::getDerivativeState ( const ct::core::StateVector< 36 > &  x,
const ct::core::ControlVector< 12 > &  u,
const double  t = 0.0 
)
overridevirtual

Referenced by clone().

◆ getDerivativeControl()

const HyQWithContactModelLinearizedReverse::state_control_matrix_t & ct::models::HyQ::HyQWithContactModelLinearizedReverse::getDerivativeControl ( const ct::core::StateVector< 36 > &  x,
const ct::core::ControlVector< 12 > &  u,
const double  t = 0.0 
)
overridevirtual

Referenced by clone().


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