BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemKinematics class

FloatingBaseSystemKinematics describes a floating base system kinematics.

The FloatingBaseSystemKinematics inherits from a generic DynamicalSystem where the State is described by a BipedalLocomotion::GenericContainer::named_tuple

NameTypeDescription
pEigen::Vector3dPosition of the base w.r.t. the inertial frame
Rmanif::SO3dRotation matrix ${} ^ I R _ {b}$ . Matrix that transform a vector whose coordinates are expressed in the base frame in the inertial frame
sEigen::VectorXdJoint positions [in rad]

The StateDerivative is described by a BipedalLocomotion::GenericContainer::named_tuple

NameTypeDescription
dpEigen::Vector3dLinear velocity of the origin of the base link whose coordinates are expressed in the Inertial frame (MIXED RERPESENTATION)
omegamanif::SO3d::Tangentbase angular velocity whose coordinates are expressed in the inertial frame (Left trivialized)
dsEigen::VectorXdJoint velocities [in rad/s]

The Input is described by a BipedalLocomotion::GenericContainer::named_tuple

NameTypeDescription
twistEigen::Matrix<double, 6, 1>Base twist expressed in mixed representation
dsEigen::VectorXdJoint velocities [in rad/s]

Base classes

template<class _Derived>
class DynamicalSystem<FloatingBaseSystemKinematics>
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::FloatingBaseSystemKinematics::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::FloatingBaseSystemKinematics::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::FloatingBaseSystemKinematics::getState() const

Get the state to the dynamical system.

Returns the current state of the dynamical system

bool BipedalLocomotion::ContinuousDynamicalSystem::FloatingBaseSystemKinematics::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::FloatingBaseSystemKinematics::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)$ .