class
#include <BipedalLocomotion/IK/SO3Task.h>
SO3Task SO3Task is a concrete implementation of the IK::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 that contains the base linear and angular velocity expressed in mixed representation and the joint velocities. The task represents the following equation
where is the angular part of the robot Jacobian and is the desired velocity. The desired velocity is chosen such that the orientation of the frame will asymptotically converge to the desired trajectory. is computed with a Proportional controller in .
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(const manif::SO3d& I_R_F, const manif::SO3d::Tangent& angularVelocity = manif::SO3d::Tangent::Zero()) -> 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 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:: IK:: SO3Task:: 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:: SO3Task:: 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:: 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::
bool BipedalLocomotion:: IK:: SO3Task:: update() override
Update the content of the element.
Returns | True in case of success, false otherwise. |
---|
bool BipedalLocomotion:: IK:: SO3Task:: setSetPoint(const manif::SO3d& I_R_F,
const manif::SO3d::Tangent& angularVelocity = manif::SO3d::Tangent::Zero())
Set the desired reference trajectory.
Parameters | |
---|---|
I_R_F | Rotation between the link and the inertial frame. |
angularVelocity | angular velocity written in mixed inertial frame. The default value is zero. |
Returns | True in case of success, false otherwise. |
std::size_t BipedalLocomotion:: IK:: 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)