18 template <
class RBDDynamics>
22 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 derivative.template head<BASE::NJOINTS>() = controlIn.template head<BASE::NJOINTS>();
typename BASE::RigidBodyPose_t RigidBodyPose_t
Definition: FixBaseVelSystem.h:29
virtual ~FixBaseVelSystem()=default
destructor
typename BASE::control_vector_t control_vector_t
Definition: FixBaseVelSystem.h:27
void computeControlledDynamics(const state_vector_t &state, const SCALAR &t, const control_vector_t &controlIn, state_vector_t &derivative) override
compute the controlled dynamics of the fixed base robotic system
Definition: FixBaseVelSystem.h:39
Base class for fix-base robot systems.
Definition: FixBaseSystemBase.h:19
typename BASE::JointAcceleration_t JointAcceleration_t
Definition: FixBaseVelSystem.h:28
typename BASE::state_vector_t state_vector_t
Definition: FixBaseVelSystem.h:26
A simple fix base robot system which is purely kinematic and actuated at VELOCITY level...
Definition: FixBaseVelSystem.h:19
core::ControlVector< CONTROL_D, SCALAR > control_vector_t
Definition: FixBaseSystemBase.h:37
JointAcceleration< NJOINTS, SCALAR > JointAcceleration_t
Definition: FixBaseSystemBase.h:38
virtual FixBaseVelSystem< RBDDynamics > * clone() const override
deep cloning
Definition: FixBaseVelSystem.h:48
FixBaseVelSystem(const FixBaseVelSystem &arg)
copy constructor
Definition: FixBaseVelSystem.h:34
tpl::RigidBodyPose< SCALAR > RigidBodyPose_t
Definition: FixBaseSystemBase.h:33
typename RBDDynamics::SCALAR SCALAR
Definition: FixBaseSystemBase.h:31
typename BASE::SCALAR SCALAR
Definition: FixBaseVelSystem.h:25
FixBaseVelSystem(const RigidBodyPose_t &basePose=RigidBodyPose_t())
constructor
Definition: FixBaseVelSystem.h:32
ct::core::StateVector< STATE_D, SCALAR > state_vector_t
Definition: FixBaseSystemBase.h:36