- 3.0.2 rigid body dynamics module.
ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR > Class Template Referenceabstract

#include <ActuatorDynamicsSymplectic.h>

Public Types

typedef ct::core::StateVector< ACT_STATE_DIMS, SCALARact_state_vector_t
 
typedef ct::core::StateVector< ACT_POS_DIM, SCALARact_pos_vector_t
 
typedef ct::core::StateVector< ACT_VEL_DIM, SCALARact_vel_vector_t
 

Public Member Functions

 ActuatorDynamicsSymplectic ()
 
virtual ~ActuatorDynamicsSymplectic ()
 
virtual ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR > * clone () const override=0
 
virtual void computePdot (const JointState< NJOINTS, SCALAR > &robotJointState, const act_state_vector_t &x, const act_vel_vector_t &v, const core::ControlVector< NJOINTS, SCALAR > &control, act_pos_vector_t &pDot)=0
 
virtual void computeVdot (const JointState< NJOINTS, SCALAR > &robotJointState, const act_state_vector_t &x, const act_pos_vector_t &p, const core::ControlVector< NJOINTS, SCALAR > &control, act_vel_vector_t &vDot)=0
 
virtual core::ControlVector< NJOINTS, SCALARcomputeControlOutput (const JointState< NJOINTS, SCALAR > &robotJointState, const act_state_vector_t &actState)=0
 output equation of the actuator More...
 
virtual ct::core::StateVector< ACT_STATE_DIMS, SCALARcomputeStateFromOutput (const JointState< NJOINTS, SCALAR > &refRobotJointState, const core::ControlVector< NJOINTS, SCALAR > &refControl)=0
 reconstruct actuator state from a desired control output and robot joint state (e.g. for initialization) More...
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ACT_STATE_DIM = ACT_STATE_DIMS
 
static const size_t ACT_POS_DIM = ACT_STATE_DIMS / 2
 
static const size_t ACT_VEL_DIM = ACT_STATE_DIMS / 2
 

Detailed Description

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
class ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >

This class covers the actuator dynamics for a robot, i.e. not the dynamics of a single actuator, but the dynamics of the collection of all actuators in the system The actuators are assumed to form a symplectic system.

Member Typedef Documentation

◆ act_state_vector_t

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
typedef ct::core::StateVector<ACT_STATE_DIMS, SCALAR> ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::act_state_vector_t

◆ act_pos_vector_t

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
typedef ct::core::StateVector<ACT_POS_DIM, SCALAR> ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::act_pos_vector_t

◆ act_vel_vector_t

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
typedef ct::core::StateVector<ACT_VEL_DIM, SCALAR> ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::act_vel_vector_t

Constructor & Destructor Documentation

◆ ActuatorDynamicsSymplectic()

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::ActuatorDynamicsSymplectic ( )
inline

◆ ~ActuatorDynamicsSymplectic()

Member Function Documentation

◆ clone()

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
virtual ActuatorDynamicsSymplectic<NJOINTS, ACT_STATE_DIMS, SCALAR>* ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::clone ( ) const
overridepure virtual

◆ computePdot()

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
virtual void ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::computePdot ( const JointState< NJOINTS, SCALAR > &  robotJointState,
const act_state_vector_t x,
const act_vel_vector_t v,
const core::ControlVector< NJOINTS, SCALAR > &  control,
act_pos_vector_t pDot 
)
pure virtual

◆ computeVdot()

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
virtual void ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::computeVdot ( const JointState< NJOINTS, SCALAR > &  robotJointState,
const act_state_vector_t x,
const act_pos_vector_t p,
const core::ControlVector< NJOINTS, SCALAR > &  control,
act_vel_vector_t vDot 
)
pure virtual

◆ computeControlOutput()

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
virtual core::ControlVector<NJOINTS, SCALAR> ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::computeControlOutput ( const JointState< NJOINTS, SCALAR > &  robotJointState,
const act_state_vector_t actState 
)
pure virtual

output equation of the actuator

Algebraic output equation for the actuator system, translating the current actuator state and the current robot state into an output control vector. Example: in an RBD setting, the controlOutput may be the actual joint torques.

Parameters
robotStatecurrent RBD state of the robot
actStatecurrent state of the actuators
controlOutputcontrol output (output side of actuator)

Referenced by ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::~ActuatorDynamicsSymplectic().

◆ computeStateFromOutput()

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
virtual ct::core::StateVector<ACT_STATE_DIMS, SCALAR> ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::computeStateFromOutput ( const JointState< NJOINTS, SCALAR > &  refRobotJointState,
const core::ControlVector< NJOINTS, SCALAR > &  refControl 
)
pure virtual

reconstruct actuator state from a desired control output and robot joint state (e.g. for initialization)

Returns
the actuator state resulting in the desired control output

Referenced by ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::~ActuatorDynamicsSymplectic().

Member Data Documentation

◆ ACT_STATE_DIM

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::ACT_STATE_DIM = ACT_STATE_DIMS
static

◆ ACT_POS_DIM

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
const size_t ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::ACT_POS_DIM = ACT_STATE_DIMS / 2
static

◆ ACT_VEL_DIM

template<size_t NJOINTS, size_t ACT_STATE_DIMS = 2 * NJOINTS, typename SCALAR = double>
const size_t ct::rbd::ActuatorDynamicsSymplectic< NJOINTS, ACT_STATE_DIMS, SCALAR >::ACT_VEL_DIM = ACT_STATE_DIMS / 2
static

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