BipedalLocomotion::TSID::R3Task class

SE3Task is a concrete implementation of the OptimalControlElement.

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 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_l \dot{\nu} + \dot{J}_l \nu = \dot{v} ^ * \]

where $J_l$ is the robot jacobian and $\dot{v} ^ *$ is the desired acceleration. The desired acceleration is chosen such that the frame will asymptotically converge to the desired trajectory. The linear component of $\dot{v} ^ *$ is computed with a standard PD controller in $R^3$ .

Base classes

struct TSIDLinearTask
TSIDLinearTask specializes a LinearTask in the case of Task based Inverse Dynamics.
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 planner.
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> I_p_F, Eigen::Ref<const Eigen::Vector3d> velocity = Eigen::Vector3d::Zero(), Eigen::Ref<const Eigen::Vector3d> acceleration = Eigen::Vector3d::Zero()) -> bool
Set the desired set-point of the trajectory.
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.
auto getControllerOutput() const -> Eigen::Ref<const Eigen::VectorXd>
Get the controller output.

Function documentation

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

Initialize the planner.

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

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

Update the content of the element.

Returns True in case of success, false otherwise.

bool BipedalLocomotion::TSID::R3Task::setSetPoint(Eigen::Ref<const Eigen::Vector3d> I_p_F, Eigen::Ref<const Eigen::Vector3d> velocity = Eigen::Vector3d::Zero(), Eigen::Ref<const Eigen::Vector3d> acceleration = Eigen::Vector3d::Zero())

Set the desired set-point of the trajectory.

Parameters
I_p_F position of the origin of the frame with respect to the inertial frame.
velocity linear velocity of the frame. The default value is set to zero.
acceleration linear acceleration of the frame. The default value is set to zero.
Returns True in case of success, false otherwise.

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

The SE3Task is an equality task.

Returns the type of the task.

bool BipedalLocomotion::TSID::R3Task::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::TSID::R3Task::setTaskControllerMode(Mode mode) override

Set the task controller mode.

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

Mode BipedalLocomotion::TSID::R3Task::getTaskControllerMode() const override

Get the task controller mode.

Returns the state of the controller

Eigen::Ref<const Eigen::VectorXd> BipedalLocomotion::TSID::R3Task::getControllerOutput() const

Get the controller output.

Returns a const reference to the controller output.