BipedalLocomotion::IK::QPFixedBaseInverseKinematics class

QPFixedBaseInverseKinematics is specialization of QPInverseKinematics class in the case of fixed base system.

The IK is here implemented as Quadratic Programming (QP) problem. The user should set the desired task with the method QPFixedBaseInverseKinematics::addTask. Each task has a given priority. Currently we support only priority equal to 0 or 1. If the task priority is set to 0 the task will be considered as a hard task, thus treated as a constraint. If the priority is equal to 1 the task will be embedded in the cost function. The class is also able to treat inequality constraints. Note that this class considers just one contact wrench as we assume the external wrench acting on only the base link. Here you can find an example of the QPFixedBaseInverseKinematics class used as velocity controller or IK

Velocity Control

Here you can find an example of the QPFixedBaseInverseKinematics interface used as a velocity controller.

Image

Inverse Kinematics

If you want to use QPFixedBaseInverseKinematics as IK you need to integrate the output velocity. System::FloatingBaseSystemKinematics and System::Integrator classes can be used to integrate the output of the IK taking into account the geometrical structure of the configuration space ( $ \mathbb{R}^3 \times SO(3) \times \mathbb{R}^n$ )

Image

Base classes

class QPInverseKinematics
QPInverseKinematics is a concrete class and implements an integration base inverse kinematics.

Constructors, destructors, conversion operators

QPFixedBaseInverseKinematics()
Constructor.
~QPFixedBaseInverseKinematics()
Destructor.

Public functions

auto initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler) -> bool override
Initialize the IK algorithm.
auto setKinDyn(std::shared_ptr<iDynTree::KinDynComputations> kinDyn) -> bool
Set the kinDynComputations object.

Function documentation

bool BipedalLocomotion::IK::QPFixedBaseInverseKinematics::initialize(std::weak_ptr<const ParametersHandler::IParametersHandler> handler) override

Initialize the IK algorithm.

Parameters
handler pointer to the IParametersHandler interface.h
Returns True in case of success, false otherwise.

bool BipedalLocomotion::IK::QPFixedBaseInverseKinematics::setKinDyn(std::shared_ptr<iDynTree::KinDynComputations> kinDyn)

Set the kinDynComputations object.

Parameters
kinDyn pointer to a kinDynComputations object.
Returns True in case of success, false otherwise.