BipedalLocomotion::ContinuousDynamicalSystem::FixedBaseDynamics class

FixedBaseDynamics describes a the dynamics of a fixed base system The FixedBaseDynamics inherits from a generic DynamicalSystem where the State is described by a BipedalLocomotion::GenericContainer::named_tuple.

NameTypeDescription
sEigen::VectorXdJoint positions [in rad]
dsEigen::VectorXdJoint velocities [in rad/s]

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

NameTypeDescription
dsEigen::VectorXdJoint velocities [in rad]
dds\ilinebr </td> <td class="markdownTableBodyCenter">Eigen::VectorXd`Joint accelerations [in rad/s^2]

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

NameTypeDescription
tauEigen::VectorXdJoint torque [in N/m]

Base classes

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

Public functions

auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler) -> bool
Initialize the FixedBaseDynamics system.
auto setRobotModel(const iDynTree::Model& model) -> bool
Set the model of the robot.
auto setMassMatrixRegularization(const Eigen::Ref<const Eigen::MatrixXd>& matrix) -> bool
Set the mass matrix regularization term.
auto dynamics(const std::chrono::nanoseconds& time, StateDerivative& stateDerivative) -> bool
Computes the floating based system dynamics.
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.

Function documentation

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

Initialize the FixedBaseDynamics system.

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

bool BipedalLocomotion::ContinuousDynamicalSystem::FixedBaseDynamics::setRobotModel(const iDynTree::Model& model)

Set the model of the robot.

Parameters
model an iDynTree robot model.
Returns true in case of success, false otherwise.

bool BipedalLocomotion::ContinuousDynamicalSystem::FixedBaseDynamics::setMassMatrixRegularization(const Eigen::Ref<const Eigen::MatrixXd>& matrix)

Set the mass matrix regularization term.

Parameters
matrix the regularization term for the mass matrix. @notice Calling this function is not mandatory. Call it only if you want to add a regularization term.
Returns true in case of success, false otherwise.

i.e. $\bar{M} = M + M _ {reg}$ . Where $M$ is the mass matrix and $M_{reg}$ is the matrix regularization term.

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

bool BipedalLocomotion::ContinuousDynamicalSystem::FixedBaseDynamics::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::FixedBaseDynamics::getState() const

Get the state to the dynamical system.

Returns the current state of the dynamical system

bool BipedalLocomotion::ContinuousDynamicalSystem::FixedBaseDynamics::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.