|
| FixBaseFDSystemSymplectic () |
| constructor More...
|
|
| FixBaseFDSystemSymplectic (std::shared_ptr< ActuatorDynamics_t > actuatorDynamics) |
| constructor including actuator dynamics More...
|
|
| FixBaseFDSystemSymplectic (const FixBaseFDSystemSymplectic &arg) |
| copy constructor More...
|
|
virtual | ~FixBaseFDSystemSymplectic () |
| destructor More...
|
|
virtual RBDDynamics & | dynamics () override |
| get dynamics More...
|
|
virtual const RBDDynamics & | dynamics () const override |
| get dynamics (const) More...
|
|
virtual void | computePdot (const state_vector_full_t &x, const v_vector_full_t &v, const control_vector_full_t &controlIn, p_vector_full_t &pDot) override |
| compute position derivatives, for both RBD system and actuator dynamics, if applicable More...
|
|
ACTUATOR_DYNAMICS_ENABLED | computeActuatorPdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const v_vector_full_t &v, const control_vector_full_t &controlIn, p_vector_full_t &pDot) |
|
ACTUATOR_DYNAMICS_DISABLED | computeActuatorPdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const v_vector_full_t &v, const control_vector_full_t &controlIn, p_vector_full_t &pDot) |
|
virtual void | computeVdot (const state_vector_full_t &x, const p_vector_full_t &p, const control_vector_full_t &controlIn, v_vector_full_t &vDot) override |
| compute velocity derivatives, for both RBD system and actuator dynamics More...
|
|
ACTUATOR_DYNAMICS_ENABLED | computeActuatorVdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const p_vector_full_t &p, const control_vector_full_t &controlIn, v_vector_full_t &vDot, control_vector_full_t &controlOut) |
|
ACTUATOR_DYNAMICS_DISABLED | computeActuatorVdot (const typename RBDDynamics::JointState_t &jState, const state_vector_full_t &x, const p_vector_full_t &p, const control_vector_full_t &controlIn, v_vector_full_t &vDot, control_vector_full_t &controlOut) |
|
virtual FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS > * | clone () const override |
| deep cloning More...
|
|
| RBDSystem ()=default |
|
virtual | ~RBDSystem ()=default |
|
| SymplecticSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL) |
|
| SymplecticSystem (std::shared_ptr< ct::core::Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::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< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &state, const time_t &t, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &derivative) override |
|
void | computePdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &v, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &pDot) |
|
virtual void | computePdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &v, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &pDot)=0 |
|
void | computeVdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &p, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &vDot) |
|
virtual void | computeVdot (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &x, const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &p, const ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > &control, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &vDot)=0 |
|
| ControlledSystem (const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL) |
|
| ControlledSystem (std::shared_ptr< ct::core::Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> controller, const SYSTEM_TYPE &type=SYSTEM_TYPE::GENERAL) |
|
| ControlledSystem (const ControlledSystem &arg) |
|
virtual | ~ControlledSystem () |
|
void | setController (const std::shared_ptr< Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> &controller) |
|
void | getController (std::shared_ptr< Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR >> &controller) const |
|
std::shared_ptr< Controller< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > > | getController () |
|
virtual void | computeDynamics (const StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &state, const time_t &t, StateVector< RBDDynamics::NJOINTS+ACT_STATE_DIM/2+RBDDynamics::NJOINTS+ACT_STATE_DIM/2, RBDDynamics::SCALAR > &derivative) override |
|
ControlVector< RBDDynamics::NJOINTS+EE_ARE_CONTROL_INPUTS *RBDDynamics::N_EE *3, RBDDynamics::SCALAR > | getLastControlAction () |
|
| 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 |
|
template<class RBDDynamics, size_t ACT_STATE_DIM = 0, bool EE_ARE_CONTROL_INPUTS = false>
class ct::rbd::FixBaseFDSystemSymplectic< RBDDynamics, ACT_STATE_DIM, EE_ARE_CONTROL_INPUTS >
A fix base rigid body system that uses forward dynamics.
A fix base rigid body system that uses forward dynamics. The control input vector is assumed to consist of
- joint torques and
- end effector forces expressed in the world frame
The state vectors of the pure RBD system and the actuator dynamics are split such that the overall system can be considered symplectic. The state vector therefore reads as
- Warning
- Make sure the actuator dynamics can be written as a symplectic system in case of using a symplectic integrator.