BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemAccelerationKinematics class

FloatingBaseSystemAccelerationKinematics describes the kinematics of a floating base system at the acceleration level.

It inherits from a generic DynamicalSystem where:

  • The State is represented as a named tuple with the following parameters:
NameTypeDescription
pEigen::Vector3dBase position expressed in the inertial frame.
Rmanif::SO3dBase orientation. The rotation matrix ( {}^I R_b ) transforms vectors expressed in the base frame to the inertial frame.
sEigen::VectorXdJoint positions (in radians).
dpEigen::Vector3dBase linear velocity (i.e., time derivative of p), expressed in the inertial frame. (mixed representation)
omegamanif::SO3d::TangentBase angular velocity, expressed in the inertial frame (using left trivialization).
dsEigen::VectorXdJoint velocities (in rad/s).
  • The StateDerivative is represented as a named tuple with the following parameters:
NameTypeDescription
dpEigen::Vector3dTime derivative of the base position (i.e., base linear velocity).
omegamanif::SO3d::TangentTime derivative of the base orientation (related to angular velocity).
dsEigen::VectorXdTime derivative of the joint positions (i.e., joint velocities).
ddpEigen::Vector3dBase linear acceleration (second time derivative of p).
domegamanif::SO3d::TangentBase angular acceleration (time derivative of omega).
ddsEigen::VectorXdJoint accelerations (in rad/s²).
  • The Input to the system is represented as a named tuple with the following parameters:
NameTypeDescription
dtwistTwist (e.g., Eigen::Matrix<double, 6, 1>)Base twist in mixed representation (typically combining both linear and angular components).
ddsEigen::VectorXdJoint accelerations (in rad/s²).

This formulation encapsulates both the instantaneous state (including positions and velocities) and their time derivatives (accelerations), while employing Lie group representations (i.e., ( SO(3) )) for handling rotations.

Base classes

template<class _Derived>
class DynamicalSystem<FloatingBaseSystemAccelerationKinematics>
DynamicalSystem defines a continuous time dynamical system, i.e.

Public functions

auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler) -> bool
Initialize the Dynamical system.
auto setState(const State& state) -> bool
Set the state of the dynamical system.
auto getState() const -> const State&
Get the state to the dynamical system.
auto setControlInput(const Input& controlInput) -> bool
Set the control input to the dynamical system.
auto dynamics(const std::chrono::nanoseconds& time, StateDerivative& stateDerivative) -> bool
Computes the floating based system dynamics.

Function documentation

bool BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemAccelerationKinematics::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler)

Initialize the Dynamical system.

Parameters
handler pointer to the parameter handler.
Returns true in case of success/false otherwise.

bool BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemAccelerationKinematics::setState(const State& state)

Set the state of the dynamical system.

Parameters
state tuple containing a const reference to the state elements.
Returns true in case of success, false otherwise.

const State& BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemAccelerationKinematics::getState() const

Get the state to the dynamical system.

Returns the current state of the dynamical system

bool BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemAccelerationKinematics::setControlInput(const Input& controlInput)

Set the control input to the dynamical system.

Parameters
controlInput the value of the control input used to compute the system dynamics.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemAccelerationKinematics::dynamics(const std::chrono::nanoseconds& time, StateDerivative& stateDerivative)

Computes the floating based system dynamics.

Parameters
time the time at witch the dynamics is computed.
stateDerivative
Returns true in case of success, false otherwise.

It return $f(x, u, t)$ .