BipedalLocomotion::IK::AngularMomentumTask class

AngularMomentumTask is a concrete implementation of the Task.

Please use this element if you want to control robot centroidal angular momentum. The task assumes perfect control of the robot velocity $\nu$ that contains the base linear and angular velocity expressed in mixed representation and the joint velocities. The task represents the following equation

\[ A_{cmm_\omega} \nu = {}^{G[A]} h_\omega ^* \]

where $A_{cmm_\omega}$ is the angular part of the robot centroidal momentum matrix ${}^{G[A]} h_\omega ^*$ is the desired centroidal angular momentum.

Base classes

struct IKLinearTask
IKLinearTask specializes a LinearTask in the case of Inverse Kinematics.

Public functions

auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) -> bool override
Initialize the task.
auto setKinDyn(std::shared_ptr<iDynTree::KinDynComputations> kinDyn) -> bool override
Set the kinDynComputations object.
auto setVariablesHandler(const System::VariablesHandler& variablesHandler) -> bool override
Set the set of variables required by the task.
auto update() -> bool override
Update the content of the element.
auto setSetPoint(Eigen::Ref<const Eigen::Vector3d> desiredAngularMomentumComponents) -> bool
Set the desired reference trajectory.
auto size() const -> std::size_t override
Get the size of the task.
auto type() const -> Type override
The AngularMomentumTask is an equality task.
auto isValid() const -> bool override
Determines the validity of the objects retrieved with getA() and getB()

Function documentation

bool BipedalLocomotion::IK::AngularMomentumTask::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) override

Initialize the task.

Parameters
paramHandler pointer to the parameters handler.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::AngularMomentumTask::setKinDyn(std::shared_ptr<iDynTree::KinDynComputations> kinDyn) override

Set the kinDynComputations object.

Parameters
kinDyn pointer to a kinDynComputations object.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::AngularMomentumTask::setVariablesHandler(const System::VariablesHandler& variablesHandler) override

Set the set of variables required by the task.

Parameters
variablesHandler reference to a variables handler.
Returns True in case of success, false otherwise.

The variables are stored in the System::VariablesHandler.

bool BipedalLocomotion::IK::AngularMomentumTask::update() override

Update the content of the element.

Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::AngularMomentumTask::setSetPoint(Eigen::Ref<const Eigen::Vector3d> desiredAngularMomentumComponents)

Set the desired reference trajectory.

Returns True in case of success, false otherwise.

std::size_t BipedalLocomotion::IK::AngularMomentumTask::size() const override

Get the size of the task.

Returns the size of the task.

(I.e the number of rows of the vector b)

Type BipedalLocomotion::IK::AngularMomentumTask::type() const override

The AngularMomentumTask is an equality task.

Returns the size of the task.

bool BipedalLocomotion::IK::AngularMomentumTask::isValid() const override

Determines the validity of the objects retrieved with getA() and getB()

Returns True if the objects are valid, false otherwise.