BipedalLocomotion::IK::JointTrackingTask class

JointsTrackingTask is a concrete implementation of the Task.

Please use this element if you want to control the desired joint position of the robot. The task represents the following equation

\[ \begin{bmatrix} 0_6 & I_n \end{bmatrix} \nu = \dot{s} ^ * \]

where $0_6$ and $I_n$ are the zero and the identity matrix. The desired joint velocity is chosen such that the joint will converge to the desired trajectory and it is computed with a standard standard PD controller in $\mathbb{R}^n$ .

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::VectorXd> jointPosition) -> bool
Set the desired setpoint.
auto setSetPoint(Eigen::Ref<const Eigen::VectorXd> jointPosition, Eigen::Ref<const Eigen::VectorXd> jointVelocity) -> bool
Set the desired setpoint.
auto size() const -> std::size_t override
Get the size of the task.
auto type() const -> Type override
The JointsTrackingTask 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::JointTrackingTask::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::JointTrackingTask::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::JointTrackingTask::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::JointTrackingTask::update() override

Update the content of the element.

Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::JointTrackingTask::setSetPoint(Eigen::Ref<const Eigen::VectorXd> jointPosition)

Set the desired setpoint.

Parameters
jointPosition vector containing the desired joint position in radians.
Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::JointTrackingTask::setSetPoint(Eigen::Ref<const Eigen::VectorXd> jointPosition, Eigen::Ref<const Eigen::VectorXd> jointVelocity)

Set the desired setpoint.

Parameters
jointPosition vector containing the desired joint position in radians.
jointVelocity vector containing the desired joint velocity in radians per second.
Returns True in case of success, false otherwise.

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

The JointsTrackingTask is an equality task.

Returns the size of the task.

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

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

Returns True if the objects are valid, false otherwise.