BipedalLocomotion::TSID::SO3Task class

SO3Task is a concrete implementation of the TSIDLinearTask.

Please use this element if you want to control the orientation of a given frame rigidly attached to the robot. The task assumes perfect control of the robot acceleration $\dot{\nu}$ that contains the base linear and angular acceleration expressed in mixed representation and the joints acceleration. The task represents the following equation

\[ J \dot{\nu} + \dot{J} \nu = \dot{\mathrm{v}} ^ * \]

where $J$ is the robot jacobian and $\dot{\mathrm{v}} ^ *$ is the desired acceleration. The desired acceleration is chosen such that the frame orientation will asymptotically converge to the desired trajectory. The angular acceleration is computed by a PD controller in $SO(3)$ .

Base classes

struct TSIDLinearTask
TSIDLinearTask specializes a LinearTask in the case of Task based Inverse Dynamics.

Public functions

auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) -> bool override
Initialize the SO3Task.
auto setKinDyn(std::shared_ptr<iDynTree::KinDynComputations> kinDyn) -> bool
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(const manif::SO3d& I_R_F, const manif::SO3d::Tangent& angularVelocity, const manif::SO3d::Tangent& angularAcceleration) -> bool
Set the desired reference point.
auto size() const -> std::size_t override
Get the size of the task.
auto type() const -> Type override
The SO3Task is an equality task.
auto isValid() const -> bool override
Determines the validity of the objects retrieved with getA() and getB()

Function documentation

bool BipedalLocomotion::TSID::SO3Task::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> paramHandler) override

Initialize the SO3Task.

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

bool BipedalLocomotion::TSID::SO3Task::setKinDyn(std::shared_ptr<iDynTree::KinDynComputations> kinDyn)

Set the kinDynComputations object.

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

bool BipedalLocomotion::TSID::SO3Task::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::TSID::SO3Task::update() override

Update the content of the element.

Returns True in case of success, false otherwise.

bool BipedalLocomotion::TSID::SO3Task::setSetPoint(const manif::SO3d& I_R_F, const manif::SO3d::Tangent& angularVelocity, const manif::SO3d::Tangent& angularAcceleration)

Set the desired reference point.

Parameters
I_R_F Rotation between the link and the inertial frame.
angularVelocity angular velocity of the frame F wr.t. the inertial frame expressed in the inertial frame.
angularAcceleration angular acceleration of the frame F wr.t. the inertial frame expressed in the inertial frame.
Returns True in case of success, false otherwise.

std::size_t BipedalLocomotion::TSID::SO3Task::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::TSID::SO3Task::type() const override

The SO3Task is an equality task.

Returns the type of the task.

bool BipedalLocomotion::TSID::SO3Task::isValid() const override

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

Returns True if the objects are valid, false otherwise.