class
JointLimitsTaskJointLimitsTask is a concrete implementation of the Task.
Please use this element if you want to ensure that the generated joint velocity will consider the joints position limits. The task represents the following equation
where and are the zero and the identity matrix. and are chosen such that robot stays within its mechanical range of motion. Following (Kanoun, 2011), we set and as follows
where and are the joints mechanical limits, and is a proportional postive gain lower than 1. , for instance, denotes that a joint angle update will not increase by more than half the distance between the current joint value and its boundaries.
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 size() const -> std::size_t override
- Get the size of the task.
- auto type() const -> Type override
- The JointsLimitsTask is an inequality task.
- auto isValid() const -> bool override
- Determines the validity of the objects retrieved with getA() and getB()
Function documentation
bool BipedalLocomotion:: IK:: JointLimitsTask:: 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:: JointLimitsTask:: 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:: JointLimitsTask:: 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:: JointLimitsTask:: update() override
Update the content of the element.
Returns | True in case of success, false otherwise. |
---|
std::size_t BipedalLocomotion:: IK:: JointLimitsTask:: 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)