BipedalLocomotion::IK::SE3Task class

SE3Task is a concrete implementation of the Task.

Please use this element if you want to control the position and the orientation of a given frame rigidly attached to the robot. 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

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

where $J$ is the robot jacobian and $\mathrm{v} ^ *$ is the desired velocity. The desired velocity is chosen such that the frame will asymptotically converge to the desired trajectory. The linear component of $\mathrm{v} ^ *$ is computed with a standard Proportional controller in $R^3$ while the angular velocity is computed by a Proportional controller in $SO(3)$ .

Base classes

struct IKLinearTask
IKLinearTask specializes a LinearTask in the case of Inverse Kinematics.
struct BipedalLocomotion::System::ITaskControllerManager
ITaskControllerManager is an interface that can help you to handle tasks containing controllers.

Public types

using Mode = System::ITaskControllerManager::Mode

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(const manif::SE3d& I_H_F, const manif::SE3d::Tangent& mixedVelocity = manif::SE3d::Tangent::Zero()) -> bool
Set the desired set-point of the trajectory.
auto setFeedback(const manif::SE3d& I_H_F) -> bool
Set the feedback for the Proportional controller.
auto setFeedback(const manif::SE3d::Translation& I_p_F) -> bool
Set the feedback for the Proportional controller.
auto setFeedback(const manif::SO3d& I_R_F) -> bool
Set the feedback for the Proportional controller.
auto size() const -> std::size_t override
Get the size of the task.
auto type() const -> Type override
The SE3Task is an equality task.
auto isValid() const -> bool override
Determines the validity of the objects retrieved with getA() and getB()
void setTaskControllerMode(Mode mode) override
Set the task controller mode.
auto getTaskControllerMode() const -> Mode override
Get the task controller mode.

Function documentation

bool BipedalLocomotion::IK::SE3Task::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. Where the generalized robot velocity is a vector containing the base spatial-velocity (expressed in mixed representation) and the joint velocities.

bool BipedalLocomotion::IK::SE3Task::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::SE3Task::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::SE3Task::update() override

Update the content of the element.

Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::SE3Task::setSetPoint(const manif::SE3d& I_H_F, const manif::SE3d::Tangent& mixedVelocity = manif::SE3d::Tangent::Zero())

Set the desired set-point of the trajectory.

Parameters
I_H_F Homogeneous transform between the link and the inertial frame.
mixedVelocity 6D-velocity written in mixed representation. The default value is zero.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::SE3Task::setFeedback(const manif::SE3d& I_H_F)

Set the feedback for the Proportional controller.

Parameters
I_H_F Homogeneous transform between the link and the inertial frame.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::SE3Task::setFeedback(const manif::SE3d::Translation& I_p_F)

Set the feedback for the Proportional controller.

Parameters
I_p_F position of the link respect to the inertial frame.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::SE3Task::setFeedback(const manif::SO3d& I_R_F)

Set the feedback for the Proportional controller.

Parameters
I_R_F orientation of the link respect to the inertial frame.
Returns True in case of success, false otherwise.

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

The SE3Task is an equality task.

Returns the size of the task.

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

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

Returns True if the objects are valid, false otherwise.

void BipedalLocomotion::IK::SE3Task::setTaskControllerMode(Mode mode) override

Set the task controller mode.

Please use this method to disable/enable the Proportional controller implemented in this task.

Mode BipedalLocomotion::IK::SE3Task::getTaskControllerMode() const override

Get the task controller mode.

Returns the state of the controller