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

A floating base rigid body system that uses forward dynamics. The input vector is assumed to consist of joint torques and end-effector forces expressed in the world. More...

#include <HyQContactModelForwardZeroSystem.h>

Inheritance diagram for ct::models::HyQ::HyQContactModelForwardZeroSystem:
ct::core::SymplecticSystem< 18, 18, 12 > ct::core::ControlledSystem< 18+18, 12, SCALAR > ct::core::System< STATE_DIM, SCALAR >

Public Types

typedef core::StateVector< STATE_DIMStateVector
 
typedef core::ControlVector< CONTROL_DIMControlVector
 
typedef core::SymplecticSystem< 18, 18, CONTROL_DIMBase
 
- Public Types inherited from ct::core::SymplecticSystem< 18, 18, 12 >
typedef Base::time_t time_t
 
- Public Types inherited from ct::core::ControlledSystem< 18+18, 12, SCALAR >
typedef std::shared_ptr< ControlledSystem< 18+18, 12, 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

 HyQContactModelForwardZeroSystem ()
 
 HyQContactModelForwardZeroSystem (const HyQContactModelForwardZeroSystem &other)
 
virtual ~HyQContactModelForwardZeroSystem ()
 
virtual HyQContactModelForwardZeroSystemclone () const override
 
virtual void computePdot (const StateVector &x, const core::StateVector< 18 > &v, const ControlVector &control, core::StateVector< 18 > &pDot) override
 
virtual void computeVdot (const StateVector &x, const core::StateVector< 18 > &p, const ControlVector &control, core::StateVector< 18 > &vDot) override
 
- Public Member Functions inherited from ct::core::SymplecticSystem< 18, 18, 12 >
 SymplecticSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 SymplecticSystem (std::shared_ptr< ct::core::Controller< 18+18, 12, SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 SymplecticSystem (const SymplecticSystem &arg)
 
virtual ~SymplecticSystem ()
 
virtual bool isSymplectic () const override
 
virtual void computeControlledDynamics (const StateVector< 18+18, SCALAR > &state, const time_t &t, const ControlVector< 12, SCALAR > &control, StateVector< 18+18, SCALAR > &derivative) override
 
void computePdot (const StateVector< 18+18, SCALAR > &x, const StateVector< 18, SCALAR > &v, StateVector< 18, SCALAR > &pDot)
 
virtual void computePdot (const StateVector< 18+18, SCALAR > &x, const StateVector< 18, SCALAR > &v, const ControlVector< 12, SCALAR > &control, StateVector< 18, SCALAR > &pDot)=0
 
void computeVdot (const StateVector< 18+18, SCALAR > &x, const StateVector< 18, SCALAR > &p, StateVector< 18, SCALAR > &vDot)
 
virtual void computeVdot (const StateVector< 18+18, SCALAR > &x, const StateVector< 18, SCALAR > &p, const ControlVector< 12, SCALAR > &control, StateVector< 18, SCALAR > &vDot)=0
 
- Public Member Functions inherited from ct::core::ControlledSystem< 18+18, 12, SCALAR >
 ControlledSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (std::shared_ptr< ct::core::Controller< 18+18, 12, SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (const ControlledSystem &arg)
 
virtual ~ControlledSystem ()
 
void setController (const std::shared_ptr< Controller< 18+18, 12, SCALAR >> &controller)
 
void getController (std::shared_ptr< Controller< 18+18, 12, SCALAR >> &controller) const
 
std::shared_ptr< Controller< 18+18, 12, SCALAR > > getController ()
 
virtual void computeDynamics (const StateVector< 18+18, SCALAR > &state, const time_t &t, StateVector< 18+18, SCALAR > &derivative) override
 
ControlVector< 12, 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
 

Static Public Attributes

static const size_t STATE_DIM = 36
 
static const size_t CONTROL_DIM = 12
 

Additional Inherited Members

- Public Attributes inherited from ct::core::SymplecticSystem< 18, 18, 12 >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef ControlledSystem< 18+18, 12, SCALARBase
 
- Public Attributes inherited from ct::core::ControlledSystem< 18+18, 12, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System< 18+18, 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< 18+18, 12, SCALAR >
std::shared_ptr< Controller< 18+18, 12, SCALAR > > controller_
 
ControlVector< 12, SCALARcontrolAction_
 
- Protected Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
SYSTEM_TYPE type_
 

Detailed Description

A floating base rigid body system that uses forward dynamics. The input vector is assumed to consist of joint torques and end-effector forces expressed in the world.

Member Typedef Documentation

◆ StateVector

◆ ControlVector

◆ Base

Constructor & Destructor Documentation

◆ HyQContactModelForwardZeroSystem() [1/2]

ct::models::HyQ::HyQContactModelForwardZeroSystem::HyQContactModelForwardZeroSystem ( )
inline

Referenced by clone().

◆ HyQContactModelForwardZeroSystem() [2/2]

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

◆ ~HyQContactModelForwardZeroSystem()

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

Member Function Documentation

◆ clone()

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

◆ computePdot()

virtual void ct::models::HyQ::HyQContactModelForwardZeroSystem::computePdot ( const StateVector x,
const core::StateVector< 18 > &  v,
const ControlVector control,
core::StateVector< 18 > &  pDot 
)
inlineoverridevirtual

◆ computeVdot()

virtual void ct::models::HyQ::HyQContactModelForwardZeroSystem::computeVdot ( const StateVector x,
const core::StateVector< 18 > &  p,
const ControlVector control,
core::StateVector< 18 > &  vDot 
)
inlineoverridevirtual

Member Data Documentation

◆ STATE_DIM

const size_t ct::models::HyQ::HyQContactModelForwardZeroSystem::STATE_DIM = 36
static

◆ CONTROL_DIM

const size_t ct::models::HyQ::HyQContactModelForwardZeroSystem::CONTROL_DIM = 12
static

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