- 3.0.2 rigid body dynamics module.
ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D > Class Template Referenceabstract

Base class for fix-base robot systems. More...

#include <FixBaseSystemBase.h>

Inheritance diagram for ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >:
ct::rbd::RBDSystem< RBDDynamics, false > ct::core::ControlledSystem< STATE_D, CONTROL_D, RBDDynamics::SCALAR > ct::core::System< STATE_DIM, SCALAR >

Public Types

using Dynamics = RBDDynamics
 
using SCALAR = typename RBDDynamics::SCALAR
 
using Base = core::ControlledSystem< STATE_D, CONTROL_D, SCALAR >
 
using RigidBodyPose_t = tpl::RigidBodyPose< SCALAR >
 
using state_vector_t = ct::core::StateVector< STATE_D, SCALAR >
 
using control_vector_t = core::ControlVector< CONTROL_D, SCALAR >
 
using JointAcceleration_t = JointAcceleration< NJOINTS, SCALAR >
 
- Public Types inherited from ct::core::ControlledSystem< STATE_D, CONTROL_D, RBDDynamics::SCALAR >
typedef std::shared_ptr< ControlledSystem< STATE_D, CONTROL_D, RBDDynamics::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

 FixBaseSystemBase (const RigidBodyPose_t &basePose=RigidBodyPose_t())
 constructor More...
 
 FixBaseSystemBase (const FixBaseSystemBase &arg)
 copy constructor More...
 
virtual ~FixBaseSystemBase ()=default
 destructor More...
 
virtual RBDDynamics & dynamics () override
 get dynamics More...
 
virtual const RBDDynamics & dynamics () const override
 get dynamics (const) More...
 
virtual void computeControlledDynamics (const ct::core::StateVector< STATE_D, SCALAR > &state, const SCALAR &t, const ct::core::ControlVector< CONTROL_D, SCALAR > &controlIn, ct::core::StateVector< STATE_D, SCALAR > &derivative) override=0
 compute the controlled dynamics of the fixed base robotic system More...
 
virtual FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D > * clone () const override=0
 deep cloning More...
 
ct::core::ControlVector< NJOINTScomputeIDTorques (const JointState< NJOINTS, SCALAR > &jState, const JointAcceleration_t &jAcc=JointAcceleration_t(Eigen::Matrix< SCALAR, NJOINTS, 1 >::Zero()))
 compute inverse dynamics torques More...
 
- Public Member Functions inherited from ct::rbd::RBDSystem< RBDDynamics, false >
 RBDSystem ()=default
 
virtual ~RBDSystem ()=default
 
- Public Member Functions inherited from ct::core::ControlledSystem< STATE_D, CONTROL_D, RBDDynamics::SCALAR >
 ControlledSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (std::shared_ptr< ct::core::Controller< STATE_D, CONTROL_D, RBDDynamics::SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL)
 
 ControlledSystem (const ControlledSystem &arg)
 
virtual ~ControlledSystem ()
 
void setController (const std::shared_ptr< Controller< STATE_D, CONTROL_D, RBDDynamics::SCALAR >> &controller)
 
void getController (std::shared_ptr< Controller< STATE_D, CONTROL_D, RBDDynamics::SCALAR >> &controller) const
 
std::shared_ptr< Controller< STATE_D, CONTROL_D, RBDDynamics::SCALAR > > getController ()
 
virtual void computeDynamics (const StateVector< STATE_D, RBDDynamics::SCALAR > &state, const time_t &t, StateVector< STATE_D, RBDDynamics::SCALAR > &derivative) override
 
virtual void computeControlledDynamics (const StateVector< STATE_D, RBDDynamics::SCALAR > &state, const time_t &t, const ControlVector< CONTROL_D, RBDDynamics::SCALAR > &control, StateVector< STATE_D, RBDDynamics::SCALAR > &derivative)=0
 
ControlVector< CONTROL_D, RBDDynamics::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
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t N_EE = RBDDynamics::N_EE
 number of end-effectors More...
 
static const size_t NJOINTS = RBDDynamics::NJOINTS
 number of joints More...
 

Protected Attributes

tpl::RigidBodyPose< SCALARbasePose_
 a "dummy" base pose which sets the robot's "fixed" position in the world More...
 
RBDDynamics dynamics_
 rigid body dynamics container More...
 
- Protected Attributes inherited from ct::core::ControlledSystem< STATE_D, CONTROL_D, RBDDynamics::SCALAR >
std::shared_ptr< Controller< STATE_D, CONTROL_D, RBDDynamics::SCALAR > > controller_
 
ControlVector< CONTROL_D, RBDDynamics::SCALARcontrolAction_
 
- Protected Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
SYSTEM_TYPE type_
 

Additional Inherited Members

- Public Attributes inherited from ct::core::ControlledSystem< STATE_D, CONTROL_D, RBDDynamics::SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef System< STATE_D, RBDDynamics::SCALARBase
 
- Public Attributes inherited from ct::core::System< STATE_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef SCALAR S
 

Detailed Description

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
class ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >

Base class for fix-base robot systems.

Member Typedef Documentation

◆ Dynamics

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
using ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::Dynamics = RBDDynamics

◆ SCALAR

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
using ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::SCALAR = typename RBDDynamics::SCALAR

◆ Base

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
using ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::Base = core::ControlledSystem<STATE_D, CONTROL_D, SCALAR>

◆ RigidBodyPose_t

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
using ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::RigidBodyPose_t = tpl::RigidBodyPose<SCALAR>

◆ state_vector_t

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
using ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::state_vector_t = ct::core::StateVector<STATE_D, SCALAR>

◆ control_vector_t

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
using ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::control_vector_t = core::ControlVector<CONTROL_D, SCALAR>

◆ JointAcceleration_t

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
using ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::JointAcceleration_t = JointAcceleration<NJOINTS, SCALAR>

Constructor & Destructor Documentation

◆ FixBaseSystemBase() [1/2]

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::FixBaseSystemBase ( const RigidBodyPose_t basePose = RigidBodyPose_t())
inline

constructor

◆ FixBaseSystemBase() [2/2]

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::FixBaseSystemBase ( const FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D > &  arg)
inline

copy constructor

◆ ~FixBaseSystemBase()

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
virtual ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::~FixBaseSystemBase ( )
virtualdefault

Member Function Documentation

◆ dynamics() [1/2]

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
virtual RBDDynamics& ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::dynamics ( )
inlineoverridevirtual

get dynamics

Implements ct::rbd::RBDSystem< RBDDynamics, false >.

◆ dynamics() [2/2]

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
virtual const RBDDynamics& ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::dynamics ( ) const
inlineoverridevirtual

get dynamics (const)

Implements ct::rbd::RBDSystem< RBDDynamics, false >.

◆ computeControlledDynamics()

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
virtual void ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::computeControlledDynamics ( const ct::core::StateVector< STATE_D, SCALAR > &  state,
const SCALAR t,
const ct::core::ControlVector< CONTROL_D, SCALAR > &  controlIn,
ct::core::StateVector< STATE_D, SCALAR > &  derivative 
)
overridepure virtual

compute the controlled dynamics of the fixed base robotic system

Referenced by ct::rbd::FixBaseSystemBase< RBDDynamics, RBDDynamics::NJOINTS, RBDDynamics::NJOINTS >::dynamics().

◆ clone()

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
virtual FixBaseSystemBase<RBDDynamics, STATE_D, CONTROL_D>* ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::clone ( ) const
overridepure virtual

◆ computeIDTorques()

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
ct::core::ControlVector<NJOINTS> ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::computeIDTorques ( const JointState< NJOINTS, SCALAR > &  jState,
const JointAcceleration_t jAcc = JointAcceleration_t(Eigen::Matrix<SCALARNJOINTS, 1>::Zero()) 
)
inline

compute inverse dynamics torques

Member Data Documentation

◆ N_EE

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::N_EE = RBDDynamics::N_EE
static

number of end-effectors

◆ NJOINTS

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
const size_t ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::NJOINTS = RBDDynamics::NJOINTS
static

◆ basePose_

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
tpl::RigidBodyPose<SCALAR> ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::basePose_
protected

a "dummy" base pose which sets the robot's "fixed" position in the world

◆ dynamics_

template<class RBDDynamics, size_t STATE_D, size_t CONTROL_D>
RBDDynamics ct::rbd::FixBaseSystemBase< RBDDynamics, STATE_D, CONTROL_D >::dynamics_
protected

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