- 3.0.2 rigid body dynamics module.
ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR > Class Template Reference

whole fix base robot state, i.e. Joint state, Actuator Dynamics (and fix-base pose) More...

#include <FixBaseRobotState.h>

Public Types

using RigidBodyPose_t = tpl::RigidBodyPose< SCALAR >
 
using JointState_t = JointState< NJOINTS, SCALAR >
 
using RBDState_t = RBDState< NJOINTS, SCALAR >
 
using actuator_state_vector_t = ct::core::StateVector< ACT_STATE_DIM, SCALAR >
 
using state_vector_t = ct::core::StateVector< NSTATE, SCALAR >
 

Public Member Functions

 FixBaseRobotState ()
 constructor More...
 
 FixBaseRobotState (const JointState_t &joints, const actuator_state_vector_t &actState=actuator_state_vector_t::Zero())
 constructor More...
 
 FixBaseRobotState (const state_vector_t &robotState)
 constructor More...
 
 FixBaseRobotState (const FixBaseRobotState &other)
 constructor More...
 
 ~FixBaseRobotState ()
 destructor More...
 
actuator_state_vector_tactuatorState ()
 accessor to actuator state More...
 
const actuator_state_vector_tactuatorState () const
 accessor to actuator state More...
 
SCALARactuatorState (size_t i)
 accessor to single element of actuator state More...
 
const SCALARactuatorState (size_t i) const
 accessor to single element of actuator state More...
 
JointState_tjoints ()
 accessor to joint state More...
 
const JointState_tjoints () const
 accessor to joint state More...
 
void setZero ()
 
template<typename T = void>
std::enable_if<(ACT_STATE_DIM==0), T >::type fromStateVector (const state_vector_t &robotState)
 conversion from dense state vector to a RobotState More...
 
template<typename T = void>
std::enable_if<(ACT_STATE_DIM > 0), T >::type fromStateVector (const state_vector_t &robotState)
 
template<typename T = state_vector_t>
std::enable_if<(ACT_STATE_DIM==0), T >::type toStateVector () const
 conversion from RobotState to dense state vector More...
 
template<typename T = state_vector_t>
std::enable_if<(ACT_STATE_DIM > 0), T >::type toStateVector () const
 
RBDState_t toRBDState (const RigidBodyPose_t &basePose=RigidBodyPose_t())
 transform full robot state to RBDState More...
 

Static Public Member Functions

static const JointState_t jointStateFromVector (const state_vector_t &robotState)
 full state vector to JointState (static) More...
 
static const RBDState_t rbdStateFromVector (const state_vector_t &robotState, const RigidBodyPose_t &basePose=RigidBodyPose_t())
 transform full robot state to RBDState (static) More...
 
static const actuator_state_vector_t actuatorStateFromVector (const state_vector_t &robotState)
 transform full robot state to a actuator state (static) More...
 
static const state_vector_t toFullState (const ct::core::StateVector< 2 *NJOINTS, SCALAR > &jointState, const actuator_state_vector_t &x_act=actuator_state_vector_t::Zero())
 transform from joint and actuator state to full state More...
 

Static Public Attributes

static const size_t NDOF = NJOINTS
 
static const size_t NSTATE = 2 * NJOINTS + ACT_STATE_DIM
 

Protected Attributes

JointState_t joints_
 the joint state More...
 
actuator_state_vector_t act_state_
 the actuator state vector More...
 

Detailed Description

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
class ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >

whole fix base robot state, i.e. Joint state, Actuator Dynamics (and fix-base pose)

Note
a base pose is not included on purpose, since that would rather be part of the "output equation" than of the state
Parameters
NJOINTSthe number of robot joints
ACT_STATE_DIMthe state dimension of the actuator
SCALARthe scalar type

Member Typedef Documentation

◆ RigidBodyPose_t

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::RigidBodyPose_t = tpl::RigidBodyPose<SCALAR>

◆ JointState_t

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::JointState_t = JointState<NJOINTS, SCALAR>

◆ RBDState_t

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::RBDState_t = RBDState<NJOINTS, SCALAR>

◆ actuator_state_vector_t

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::actuator_state_vector_t = ct::core::StateVector<ACT_STATE_DIM, SCALAR>

◆ state_vector_t

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::state_vector_t = ct::core::StateVector<NSTATE, SCALAR>

Constructor & Destructor Documentation

◆ FixBaseRobotState() [1/4]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::FixBaseRobotState ( )
inline

constructor

◆ FixBaseRobotState() [2/4]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::FixBaseRobotState ( const JointState_t joints,
const actuator_state_vector_t actState = actuator_state_vector_t::Zero() 
)
inline

constructor

◆ FixBaseRobotState() [3/4]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::FixBaseRobotState ( const state_vector_t robotState)
inline

◆ FixBaseRobotState() [4/4]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::FixBaseRobotState ( const FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR > &  other)
inline

constructor

◆ ~FixBaseRobotState()

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::~FixBaseRobotState ( )
inline

destructor

Member Function Documentation

◆ jointStateFromVector()

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
static const JointState_t ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::jointStateFromVector ( const state_vector_t robotState)
inlinestatic

◆ rbdStateFromVector()

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
static const RBDState_t ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::rbdStateFromVector ( const state_vector_t robotState,
const RigidBodyPose_t basePose = RigidBodyPose_t() 
)
inlinestatic

◆ actuatorStateFromVector()

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
static const actuator_state_vector_t ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::actuatorStateFromVector ( const state_vector_t robotState)
inlinestatic

transform full robot state to a actuator state (static)

Referenced by TEST().

◆ toFullState()

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
static const state_vector_t ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::toFullState ( const ct::core::StateVector< 2 *NJOINTS, SCALAR > &  jointState,
const actuator_state_vector_t x_act = actuator_state_vector_t::Zero() 
)
inlinestatic

transform from joint and actuator state to full state

◆ actuatorState() [1/4]

◆ actuatorState() [2/4]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
const actuator_state_vector_t& ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::actuatorState ( ) const
inline

◆ actuatorState() [3/4]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
SCALAR& ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::actuatorState ( size_t  i)
inline

accessor to single element of actuator state

References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::act_state_.

◆ actuatorState() [4/4]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
const SCALAR& ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::actuatorState ( size_t  i) const
inline

accessor to single element of actuator state

References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::act_state_.

◆ joints() [1/2]

◆ joints() [2/2]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
const JointState_t& ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::joints ( ) const
inline

◆ setZero()

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
void ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::setZero ( )
inline

◆ fromStateVector() [1/2]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
template<typename T = void>
std::enable_if<(ACT_STATE_DIM == 0), T>::type ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::fromStateVector ( const state_vector_t robotState)
inline

◆ fromStateVector() [2/2]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
template<typename T = void>
std::enable_if<(ACT_STATE_DIM > 0), T>::type ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::fromStateVector ( const state_vector_t robotState)
inline

◆ toStateVector() [1/2]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
template<typename T = state_vector_t>
std::enable_if<(ACT_STATE_DIM == 0), T>::type ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::toStateVector ( ) const
inline

◆ toStateVector() [2/2]

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
template<typename T = state_vector_t>
std::enable_if<(ACT_STATE_DIM > 0), T>::type ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::toStateVector ( ) const
inline

◆ toRBDState()

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
RBDState_t ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::toRBDState ( const RigidBodyPose_t basePose = RigidBodyPose_t())
inline

Member Data Documentation

◆ NDOF

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
const size_t ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::NDOF = NJOINTS
static

◆ NSTATE

template<size_t NJOINTS, size_t ACT_STATE_DIM = 0, typename SCALAR = double>
const size_t ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::NSTATE = 2 * NJOINTS + ACT_STATE_DIM
static

Referenced by TEST().

◆ joints_

◆ act_state_


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