- 3.0.2 rigid body dynamics module.
|
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_t & | actuatorState () |
accessor to actuator state More... | |
const actuator_state_vector_t & | actuatorState () const |
accessor to actuator state More... | |
SCALAR & | actuatorState (size_t i) |
accessor to single element of actuator state More... | |
const SCALAR & | actuatorState (size_t i) const |
accessor to single element of actuator state More... | |
JointState_t & | joints () |
accessor to joint state More... | |
const JointState_t & | joints () 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... | |
whole fix base robot state, i.e. Joint state, Actuator Dynamics (and fix-base pose)
NJOINTS | the number of robot joints |
ACT_STATE_DIM | the state dimension of the actuator |
SCALAR | the scalar type |
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::RigidBodyPose_t = tpl::RigidBodyPose<SCALAR> |
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::JointState_t = JointState<NJOINTS, SCALAR> |
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::RBDState_t = RBDState<NJOINTS, SCALAR> |
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::actuator_state_vector_t = ct::core::StateVector<ACT_STATE_DIM, SCALAR> |
using ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::state_vector_t = ct::core::StateVector<NSTATE, SCALAR> |
|
inline |
constructor
|
inline |
constructor
|
inline |
constructor
References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::fromStateVector().
|
inline |
constructor
|
inline |
destructor
|
inlinestatic |
full state vector to JointState (static)
References ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), and ct::rbd::JointState< NJOINTS, SCALAR >::getVelocities().
Referenced by ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::rbdStateFromVector(), and TEST().
|
inlinestatic |
transform full robot state to RBDState (static)
References ct::rbd::RBDState< NJOINTS, SCALAR >::basePose(), ct::rbd::RBDState< NJOINTS, SCALAR >::joints(), ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::jointStateFromVector(), and ct::rbd::RBDState< NJOINTS, SCALAR >::setZero().
|
inlinestatic |
transform full robot state to a actuator state (static)
Referenced by TEST().
|
inlinestatic |
transform from joint and actuator state to full state
|
inline |
accessor to actuator state
References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::act_state_.
Referenced by ct::rbd::FixBaseFDSystem< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeActuatorDynamics(), and ct::rbd::FixBaseNLOC< FIX_BASE_FD_SYSTEM >::initializeDirectInterpolation().
|
inline |
accessor to actuator state
References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::act_state_.
|
inline |
accessor to single element of actuator state
References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::act_state_.
|
inline |
accessor to single element of actuator state
References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::act_state_.
|
inline |
accessor to joint state
References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::joints_.
Referenced by ct::rbd::FixBaseFDSystem< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeActuatorDynamics(), ct::rbd::FixBaseFDSystem< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >::computeControlledDynamics(), ct::rbd::FixBaseNLOC< FIX_BASE_FD_SYSTEM >::initializeDirectInterpolation(), and ct::rbd::FixBaseNLOC< FIX_BASE_FD_SYSTEM >::initializeSteadyPose().
|
inline |
accessor to joint state
References ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::joints_.
|
inline |
|
inline |
conversion from dense state vector to a RobotState
References ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), ct::rbd::JointState< NJOINTS, SCALAR >::getVelocities(), and ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::joints_.
Referenced by ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::FixBaseRobotState().
|
inline |
|
inline |
conversion from RobotState to dense state vector
References ct::rbd::JointState< NJOINTS, SCALAR >::getPositions(), ct::rbd::JointState< NJOINTS, SCALAR >::getVelocities(), and ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::joints_.
Referenced by ct::rbd::FixBaseNLOC< FIX_BASE_FD_SYSTEM >::initializeDirectInterpolation(), and ct::rbd::FixBaseNLOC< FIX_BASE_FD_SYSTEM >::initializeSteadyPose().
|
inline |
|
inline |
|
static |
|
static |
Referenced by TEST().
|
protected |
the joint state
Referenced by ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::fromStateVector(), ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::joints(), ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::setZero(), ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::toRBDState(), and ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::toStateVector().
|
protected |
the actuator state vector
Referenced by ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::actuatorState(), ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::fromStateVector(), ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::setZero(), and ct::rbd::FixBaseRobotState< NJOINTS, ACT_STATE_DIM, SCALAR >::toStateVector().