iDynTree::InverseKinematics class

NLP-based Inverse kinematics.

Given a mechanical structure configuration

\[ q \in \operatorname{SE}(3) \times \mathbb{R}^n \]

and possibly multiple target frames

\[ F_i^d \in \operatorname{SE}(3) \]

the inverse kinematics is responsible to find the configuration $ q^* $ such that

\[ F_i(q^*) = F_i^d \forall i, \]

where the meaning of the $=$ and $\forall$ depends on the resolution mode and on the references specified

Example

//Allocate an inverse kinematics object
iDynTree::InverseKinematric ik;

Constructors, destructors, conversion operators

InverseKinematics()
~InverseKinematics()

Public functions

auto loadModelFromFile(const std::string& filename, const std::vector<std::string>& consideredJoints = std::vector<std::string>(), const std::string& filetype = "urdf") -> bool
Loads the kinematic model from an external file.
auto setModel(const iDynTree::Model& model, const std::vector<std::string>& consideredJoints = std::vector<std::string>()) -> bool
set the kinematic model to be used in the optimization
auto setJointLimits(std::vector<std::pair<double, double>>& jointLimits) -> bool
auto getJointLimits(std::vector<std::pair<double, double>>& jointLimits) -> bool
void clearProblem()
auto setFloatingBaseOnFrameNamed(const std::string& floatingBaseFrameName) -> bool
auto setCurrentRobotConfiguration(const iDynTree::Transform& baseConfiguration, const iDynTree::VectorDynSize& jointConfiguration) -> bool
auto setCurrentRobotConfiguration(iDynTree::MatrixView<const double> baseConfiguration, iDynTree::Span<const double> jointConfiguration) -> bool
auto setJointConfiguration(const std::string& jointName, const double jointConfiguration) -> bool
void setRotationParametrization(enum InverseKinematicsRotationParametrization parametrization)
auto rotationParametrization() -> enum InverseKinematicsRotationParametrization
auto setDesiredFullJointsConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, double weight = -1.0) -> bool
auto setDesiredFullJointsConfiguration(iDynTree::Span<const double> desiredJointConfiguration, double weight = -1.0) -> bool
auto setDesiredFullJointsConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, const iDynTree::VectorDynSize& weights) -> bool
auto setDesiredFullJointsConfiguration(iDynTree::Span<const double> desiredJointConfiguration, iDynTree::Span<const double> weights) -> bool
auto setDesiredReducedJointConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, double weight = -1.0) -> bool
auto setDesiredReducedJointConfiguration(iDynTree::Span<const double> desiredJointConfiguration, double weight = -1.0) -> bool
auto setDesiredReducedJointConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, const iDynTree::VectorDynSize& weights) -> bool
auto setDesiredReducedJointConfiguration(iDynTree::Span<const double> desiredJointConfiguration, iDynTree::Span<const double> weights) -> bool
auto setFullJointsInitialCondition(const iDynTree::Transform* baseTransform, const iDynTree::VectorDynSize* initialCondition) -> bool
auto setReducedInitialCondition(const iDynTree::Transform* baseTransform, const iDynTree::VectorDynSize* initialCondition) -> bool
auto solve() -> bool
auto getPoseForFrame(const std::string& frameName, iDynTree::Transform& transform) -> bool
auto getPoseForFrame(const std::string& frameName, iDynTree::MatrixView<double> transform) -> bool
auto fullModel() const -> const Model&
auto reducedModel() const -> const Model&
void setCOMTarget(const iDynTree::Position& desiredPosition, double weight = 1.0)
auto setCOMTarget(iDynTree::Span<const double> desiredPosition, double weight = 1.0) -> bool
void setCOMAsConstraint(bool asConstraint = true)
void setCOMAsConstraintTolerance(double tolerance = 1e-8)
auto isCOMAConstraint() -> bool
auto isCOMTargetActive() -> bool
void deactivateCOMTarget()
void setCOMConstraintProjectionDirection(const iDynTree::Vector3& direction)
auto setCOMConstraintProjectionDirection(iDynTree::Span<const double> direction) -> bool

Function documentation

iDynTree::InverseKinematics::InverseKinematics()

Default constructor

iDynTree::InverseKinematics::~InverseKinematics()

Destructor

bool iDynTree::InverseKinematics::loadModelFromFile(const std::string& filename, const std::vector<std::string>& consideredJoints = std::vector<std::string>(), const std::string& filetype = "urdf")

Loads the kinematic model from an external file.

Parameters
filename
consideredJoints in list of internal joints describing which joints are optimized
filetype in (optional) explicit definition of the type of the loaded file. Only "urdf" is supported at the moment.
Returns true if successful. False otherwise

You can specify an optional list specifying which joints are considered as optimization variables (all the joints not contained in the list are considered fixed joint). If the vector is empty all the joints in the model will be considered as optimization variables.

bool iDynTree::InverseKinematics::setModel(const iDynTree::Model& model, const std::vector<std::string>& consideredJoints = std::vector<std::string>())

set the kinematic model to be used in the optimization

Parameters
model the kinematic model to be used in the optimization
consideredJoints
Returns true if successful. False otherwise

All the degrees of freedom listed in the second parameters will be used as optimization variables. If the vector is empty, all the joints will be used.

bool iDynTree::InverseKinematics::setJointLimits(std::vector<std::pair<double, double>>& jointLimits)

Parameters
jointLimits vector of new joint limits to be imposed
Returns true if successfull, false otherwise

Set new joint limits

bool iDynTree::InverseKinematics::getJointLimits(std::vector<std::pair<double, double>>& jointLimits)

Parameters
jointLimits vector of current joint limits
Returns true if successfull, false otherwise

Get current joint limits

void iDynTree::InverseKinematics::clearProblem()

Reset the variables.

bool iDynTree::InverseKinematics::setCurrentRobotConfiguration(const iDynTree::Transform& baseConfiguration, const iDynTree::VectorDynSize& jointConfiguration)

Parameters
baseConfiguration transformation identifying the base pose with respect to the world frame
jointConfiguration
Returns true if successful, false otherwise.

Sets the robot current configuration

bool iDynTree::InverseKinematics::setCurrentRobotConfiguration(iDynTree::MatrixView<const double> baseConfiguration, iDynTree::Span<const double> jointConfiguration)

Parameters
baseConfiguration the 4x4 homogeneous transformation that transforms position vectors expressed in the base reference frame in position frames expressed in the world reference frame (i.e. pos_world = baseConfiguration*pos_base).
jointConfiguration
Returns true if successful, false otherwise.

Sets the robot current configuration

bool iDynTree::InverseKinematics::setJointConfiguration(const std::string& jointName, const double jointConfiguration)

Parameters
jointName name of the joint
jointConfiguration new value for the joint
Returns true if successful, false otherwise.

Set configuration for the specified joint

bool iDynTree::InverseKinematics::setDesiredFullJointsConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, double weight = -1.0)

Parameters
desiredJointConfiguration in configuration for the joints
weight in weight for the joint configuration cost. If it is not passed, the previous passed value will be mantained. If the value was never passed, its value is 1e-6 .
Returns true if successful, false otherwise.

Sets a desired final configuration for all the robot joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

bool iDynTree::InverseKinematics::setDesiredFullJointsConfiguration(iDynTree::Span<const double> desiredJointConfiguration, double weight = -1.0)

Parameters
desiredJointConfiguration in configuration for the joints
weight in weight for the joint configuration cost. If it is not passed, the previous passed value will be mantained. If the value was never passed, its value is 1e-6 .
Returns true if successful, false otherwise.

Sets a desired final configuration for all the robot joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

bool iDynTree::InverseKinematics::setDesiredFullJointsConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, const iDynTree::VectorDynSize& weights)

Parameters
desiredJointConfiguration in configuration for the joints
weights in Joint-wise weights for the joint configuration cost. This vector should have the same dimension of the desiredJointConfiguration. If one of its elements is negative, the previous value will be kept. If the value was never passed, its value is 1e-6, equal for all joints.
Returns true if successful, false otherwise.

Sets a desired final configuration for all the robot joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

bool iDynTree::InverseKinematics::setDesiredFullJointsConfiguration(iDynTree::Span<const double> desiredJointConfiguration, iDynTree::Span<const double> weights)

Parameters
desiredJointConfiguration in configuration for the joints
weights in Joint-wise weights for the joint configuration cost. This vector should have the same dimension of the desiredJointConfiguration. If one of its elements is negative, the previous value will be kept. If the value was never passed, its value is 1e-6, equal for all joints.
Returns true if successful, false otherwise.

Sets a desired final configuration for all the robot joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

bool iDynTree::InverseKinematics::setDesiredReducedJointConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, double weight = -1.0)

Parameters
desiredJointConfiguration in configuration for the joints
weight in weight for the joint configuration cost. If it is not passed, the previous passed value will be mantained. If the value was never passed, its value is 1e-6 .
Returns true if successful, false otherwise.

Sets a desired final configuration for the set of considered joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

bool iDynTree::InverseKinematics::setDesiredReducedJointConfiguration(iDynTree::Span<const double> desiredJointConfiguration, double weight = -1.0)

Parameters
desiredJointConfiguration in configuration for the joints
weight in weight for the joint configuration cost. If it is not passed, the previous passed value will be mantained. If the value was never passed, its value is 1e-6 .
Returns true if successful, false otherwise.

Sets a desired final configuration for the set of considered joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

bool iDynTree::InverseKinematics::setDesiredReducedJointConfiguration(const iDynTree::VectorDynSize& desiredJointConfiguration, const iDynTree::VectorDynSize& weights)

Parameters
desiredJointConfiguration in configuration for the joints
weights in Joint-wise weights for the joint configuration cost. This vector should have the same dimension of the desiredJointConfiguration. If one of its elements is negative, the previous value will be kept. If the value was never passed, its value is 1e-6, equal for all joints.
Returns true if successful, false otherwise.

Sets a desired final configuration for the set of considered joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

bool iDynTree::InverseKinematics::setDesiredReducedJointConfiguration(iDynTree::Span<const double> desiredJointConfiguration, iDynTree::Span<const double> weights)

Parameters
desiredJointConfiguration in configuration for the joints
weights in Joint-wise weights for the joint configuration cost. This vector should have the same dimension of the desiredJointConfiguration. If one of its elements is negative, the previous value will be kept. If the value was never passed, its value is 1e-6, equal for all joints.
Returns true if successful, false otherwise.

Sets a desired final configuration for the set of considered joints.

The solver will try to obtain solutions as similar to the specified configuration as possible

void iDynTree::InverseKinematics::setCOMConstraintProjectionDirection(const iDynTree::Vector3& direction)

Parameters
direction vector along which we want to project a point

Set the directions along which a point will be projected.

void iDynTree::InverseKinematics::setMaxIterations(const int max_iter)

Sets Maximum Iteration.

Parameters
max_iter exits if iter>=max_iter (max_iter<0 disables this check).

The default value for this parameter is 3000 .

int iDynTree::InverseKinematics::maxIterations() const

Retrieves the current value of Maximum Iteration.

Returns max_iter.

void iDynTree::InverseKinematics::setMaxCPUTime(const double max_cpu_time)

Sets Maximum CPU seconds.

Parameters
max_cpu_time exits if cpu_time>=max_cpu_time given in seconds.

The default value for this parameter is \frac$ 10^{6} \frac$ .

double iDynTree::InverseKinematics::maxCPUTime() const

Retrieves the current value of Maximum CPU seconds.

Returns max_cpu_time.

void iDynTree::InverseKinematics::setCostTolerance(const double tol)

Sets cost function tolerance.

Parameters
tol tolerance.

The default value for this parameter is \frac$ 10^{-8} \frac$ .

double iDynTree::InverseKinematics::costTolerance() const

Retrieves cost function tolerance.

Returns tolerance.

void iDynTree::InverseKinematics::setConstraintsTolerance(const double constr_tol)

Sets constraints tolerance.

The default value for this parameter is \frac$ 10^{-4} \frac$ .

double iDynTree::InverseKinematics::constraintsTolerance() const

Retrieves constraints tolerance.

Returns tolerance.

void iDynTree::InverseKinematics::setVerbosity(const unsigned int verbose)

Parameters
verbose is a integer number which progressively enables different levels of warning messages or status dump. The larger this value the more detailed is the output.

Sets Verbosity.

bool iDynTree::InverseKinematics::addFrameConstraint(const std::string& frameName)

Parameters
frameName the frame name
Returns true if successful, false otherwise.

Adds a (constancy) constraint for the specified frame

The constraint is $ {}^w X_{frame}(q) = {}^w X_{frame}(q^0) $ where the robot configuration $q$ is the one specified with setRobotConfiguration

bool iDynTree::InverseKinematics::addFrameConstraint(const std::string& frameName, const iDynTree::Transform& constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the transform to associate to the constraint.
Returns true if successful, false otherwise.

Adds a (constancy) constraint for the specified frame

The homogeneous trasformation of the specified frame w.r.t. the inertial frame will remain constant and equal to the specified second parameter

bool iDynTree::InverseKinematics::addFrameConstraint(const std::string& frameName, iDynTree::MatrixView<const double> constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the 4x4 homogeneous transformation to associate to the constraint.
Returns true if successful, false otherwise.

Adds a (constancy) constraint for the specified frame

The homogeneous trasformation of the specified frame w.r.t. the inertial frame will remain constant and equal to the specified second parameter

bool iDynTree::InverseKinematics::addFramePositionConstraint(const std::string& frameName, const iDynTree::Position& constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the position associated to the constraint
Returns true if successful, false otherwise.

Adds a (constancy) position constraint for the specified frame

Only the position component of the frame is constrained

bool iDynTree::InverseKinematics::addFramePositionConstraint(const std::string& frameName, iDynTree::Span<const double> constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the position associated to the constraint
Returns true if successful, false otherwise.

Adds a (constancy) position constraint for the specified frame

Only the position component of the frame is constrained

bool iDynTree::InverseKinematics::addFramePositionConstraint(const std::string& frameName, const iDynTree::Transform& constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the position associated to the constraint
Returns true if successful, false otherwise.

Adds a (constancy) position constraint for the specified frame

Only the position component of the frame is constrained

bool iDynTree::InverseKinematics::addFramePositionConstraint(const std::string& frameName, iDynTree::MatrixView<const double> constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the 4x4 homogeneous transformation to associate to the constraint.
Returns true if successful, false otherwise.

Adds a (constancy) position constraint for the specified frame

Only the position component of the frame is constrained

bool iDynTree::InverseKinematics::addFrameRotationConstraint(const std::string& frameName, const iDynTree::Rotation& constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the orientation associated to the constraint
Returns true if successful, false otherwise.

Adds a (constancy) orientation constraint for the specified frame

Only the orientation component of the frame is constrained

bool iDynTree::InverseKinematics::addFrameRotationConstraint(const std::string& frameName, iDynTree::MatrixView<const double> constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue if constraintValue is a 4x4 matrix is considered as homogeneous transformation, if it is a 3x3 is considered as rotation matrix.
Returns true if successful, false otherwise.

Adds a (constancy) orientation constraint for the specified frame

Only the orientation component of the frame is constrained

bool iDynTree::InverseKinematics::addFrameRotationConstraint(const std::string& frameName, const iDynTree::Transform& constraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
constraintValue the orientation associated to the constraint
Returns true if successful, false otherwise.

Adds a (constancy) orientation constraint for the specified frame

Only the orientation component of the frame is constrained

bool iDynTree::InverseKinematics::activateFrameConstraint(const std::string& frameName, iDynTree::MatrixView<const double> newConstraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
newConstraintValue the 4x4 homogeneous transformation to associate to the pose of the constrained frame (r) in the world frame (w), i.e. ʷHᵣ.
Returns true if successful, false otherwise.

Activate a given constraint previously added with an addFrame**Constraint method.

bool iDynTree::InverseKinematics::activateFrameConstraint(const std::string& frameName, const Transform& newConstraintValue)

Parameters
frameName the name of the frame on which to attach the constraint
newConstraintValue the pose of the constrained frame (r) in the world frame (w), i.e. ʷHᵣ .
Returns true if successful, false otherwise.

Activate a given constraint previously added with an addFrame**Constraint method.

bool iDynTree::InverseKinematics::deactivateFrameConstraint(const std::string& frameName)

Parameters
frameName the name of the frame on which to attach the constraint
Returns true if successful (i.e. the constraint is present) , false otherwise.

Deactivate a given constraint previously added with an addFrame**Constraint method.

bool iDynTree::InverseKinematics::isFrameConstraintActive(const std::string& frameName) const

Parameters
frameName the name of the constrained frame
Returns true if the constraint is active, false if it is not active or it does not exist, or if the frame does not exist.

Check if a given constraint is active or not.

bool iDynTree::InverseKinematics::addCenterOfMassProjectionConstraint(const std::string& firstSupportFrame, const Polygon& firstSupportPolygon, const iDynTree::Direction xAxisOfPlaneInWorld, const iDynTree::Direction yAxisOfPlaneInWorld, const iDynTree::Position originOfPlaneInWorld = iDynTree::Position::Zero())

Specialization of addCenterOfMassProjectionConstraint when only two support frames are specified.

bool iDynTree::InverseKinematics::addCenterOfMassProjectionConstraint(const std::string& firstSupportFrame, const Polygon& firstSupportPolygon, const std::string& secondSupportFrame, const Polygon& secondSupportPolygon, const iDynTree::Direction xAxisOfPlaneInWorld, const iDynTree::Direction yAxisOfPlaneInWorld, const iDynTree::Position originOfPlaneInWorld = iDynTree::Position::Zero())

Specialization of addCenterOfMassProjectionConstraint when only two support frames are specified.

bool iDynTree::InverseKinematics::addCenterOfMassProjectionConstraint(const std::vector<std::string>& supportFrames, const std::vector<Polygon>& supportPolygons, const iDynTree::Direction xAxisOfPlaneInWorld, const iDynTree::Direction yAxisOfPlaneInWorld, const iDynTree::Position originOfPlaneInWorld)

Add a constant inequality constraint on the projection of the center of mass, assuming an arbitrary number of support links.

If a subset of the supportFrames is contrained by a FrameConstraint (both position and constraint) and such constraint is active, this constraint adds a inequality constraint to ensure that the center of mass projection lies on the convex hull of the contact polygons.

double iDynTree::InverseKinematics::getCenterOfMassProjectionMargin()

Get the distance between the projection of the center of mass projection for the current configuration (set through setRobotConfiguration) and the limit of the convex hull (positive if the center of mass is inside the convex hull, negative if the com is outside the convex hull).

If no constraint has been added through a call to addCenterOfMassProjectionConstraint, return 0.0 .

bool iDynTree::InverseKinematics::getCenterOfMassProjectConstraintConvexHull(Polygon2D& convexHull)

Get the active convex hull.

Parameters
convexHull out constraint convex hull for the projected center of mass.
Returns true if the center of mass projection constraint is active, false otherwise.

The convex hull returned is expressed in the plane defined by the xAxisOfPlaneInWorld, yAxisOfPlaneInWorld and originOfPlaneInWorld arguments of the addCenterOfMassProjectionConstraint methods.

The transform world_H_constraintFrame that describe how the support polygon for each support frame is transformed in the world frame are the one set in the addFrameConstraint method.

bool iDynTree::InverseKinematics::addTarget(const std::string& frameName, const iDynTree::Transform& targetValue, const double positionWeight = 1.0, const double rotationWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the frame should reach
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds a target for the specified frame

bool iDynTree::InverseKinematics::addTarget(const std::string& frameName, iDynTree::MatrixView<const double> targetValue, const double positionWeight = 1.0, const double rotationWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue the 4x4 homogeneous transformation to associate to target.
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds a target for the specified frame

bool iDynTree::InverseKinematics::addPositionTarget(const std::string& frameName, const iDynTree::Position& targetValue, const double positionWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the origin of the frame frameName should reach
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds a position (3D) target for the specified frame

bool iDynTree::InverseKinematics::addPositionTarget(const std::string& frameName, iDynTree::Span<const double> targetValue, const double positionWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the origin of the frame frameName should reach
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds a position (3D) target for the specified frame

bool iDynTree::InverseKinematics::addPositionTarget(const std::string& frameName, const iDynTree::Transform& targetValue, const double positionWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the origin of the frame frameName should reach
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds a position (3D) target for the specified frame

bool iDynTree::InverseKinematics::addPositionTarget(const std::string& frameName, iDynTree::MatrixView<const double> targetValue, const double positionWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue the 4x4 homogeneous transformation to associate to target.
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds a target for the specified frame

bool iDynTree::InverseKinematics::addRotationTarget(const std::string& frameName, const iDynTree::Rotation& targetValue, const double rotationWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the orientation of the frame frameName should reach
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds an orientation target for the specified frame

bool iDynTree::InverseKinematics::addRotationTarget(const std::string& frameName, const iDynTree::Transform& targetValue, const double rotationWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the orientation of the frame frameName should reach
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds an orientation target for the specified frame

This call is equivalent to call addRotationTarget(frameName, targetValue.rotation());

bool iDynTree::InverseKinematics::addRotationTarget(const std::string& frameName, iDynTree::MatrixView<const double> targetValue, const double rotationWeight = 1.0)

Parameters
frameName the name of the frame which represents the target
targetValue if constraintValue is a 4x4 matrix is considered as homogeneous transformation, if it is a 3x3 is considered as rotation matrix.
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is 1.0
Returns true if successful, false otherwise.

Adds an orientation target for the specified frame

This call is equivalent to call addRotationTarget(frameName, targetValue.rotation());

bool iDynTree::InverseKinematics::updateTarget(const std::string& frameName, const iDynTree::Transform& targetValue, const double positionWeight = -1.0, const double rotationWeight = -1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the frame should reach
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the the last one previously set.
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the the last one previously set.
Returns true if successful, false otherwise, for example if the specified frame target was not previously added with addTarget .

Update the desired target and weights for the specified frame.

bool iDynTree::InverseKinematics::updateTarget(const std::string& frameName, iDynTree::MatrixView<const double> targetValue, const double positionWeight = -1.0, const double rotationWeight = -1.0)

Parameters
frameName the name of the frame which represents the target
targetValue 4x4 homogeneous transformation to associate to target.
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the the last one previously set.
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the the last one previously set.
Returns true if successful, false otherwise, for example if the specified frame target was not previously added with addTarget .

Update the desired target and weights for the specified frame.

bool iDynTree::InverseKinematics::updatePositionTarget(const std::string& frameName, const iDynTree::Position& targetValue, const double positionWeight = -1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the origin of the frame frameName should reach
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the last one previously set.
Returns true if successful, false otherwise, for example if the specified frame target was not previously added with addTarget or addPositionTarget .

Update the position (3D) target for the specified frame

bool iDynTree::InverseKinematics::updatePositionTarget(const std::string& frameName, iDynTree::Span<const double> targetValue, const double positionWeight = -1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the origin of the frame frameName should reach
positionWeight in if the position part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the last one previously set.
Returns true if successful, false otherwise, for example if the specified frame target was not previously added with addTarget or addPositionTarget .

Update the position (3D) target for the specified frame

bool iDynTree::InverseKinematics::updateRotationTarget(const std::string& frameName, const iDynTree::Rotation& targetValue, const double rotationWeight = -1.0)

Parameters
frameName the name of the frame which represents the target
targetValue value that the orientation of the frame frameName should reach
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the last one previously set.
Returns true if successful, false otherwise, for example if the specified frame target was not previously added with addTarget or addRotationTarget .

Update an orientation target for the specified frame

bool iDynTree::InverseKinematics::updateRotationTarget(const std::string& frameName, iDynTree::MatrixView<const double> targetValue, const double rotationWeight = -1.0)

Parameters
frameName the name of the frame which represents the target
targetValue 3x3 rotation matrix representing the orientation of the frame frameName should reach
rotationWeight in if the rotation part of the target is handled as a term in the cost function, this specify the weight of this term in the cost function. Default value is the last one previously set.
Returns true if successful, false otherwise, for example if the specified frame target was not previously added with addTarget or addRotationTarget .

Update an orientation target for the specified frame

void iDynTree::InverseKinematics::setDefaultTargetResolutionMode(enum iDynTree::InverseKinematicsTreatTargetAsConstraint mode)

Parameters
mode the target resolution mode
Returns true if successful, false otherwise.

Specify the default method to solve all the specified targets

Targets can be solved fully as cost, partially (position or orientation) as cost and the other component as hard constraint or fully as hard constraints

enum iDynTree::InverseKinematicsTreatTargetAsConstraint iDynTree::InverseKinematics::defaultTargetResolutionMode()

Returns the current default method to solve targets

Returns the default method to solve all the specified targets

bool iDynTree::InverseKinematics::setTargetResolutionMode(const std::string& targetName, enum InverseKinematicsTreatTargetAsConstraint mode)

Parameters
targetName the name (frame) identified the target
mode the target resolution mode
Returns true if successful, false otherwise, for example if the specified frame target was not previously added with addTarget or addRotationTarget .

Specify the method to solve the specified target

Targets can be solved fully as cost, partially (position or orientation) as cost and the other component as hard constraint or fully as hard constraints

enum InverseKinematicsTreatTargetAsConstraint iDynTree::InverseKinematics::targetResolutionMode(const std::string& frameName)

Returns the current target resolution mode, or InverseKinematicsTreatTargetAsConstraintNone if the target cannot be found

Return the target resolution mode

void iDynTree::InverseKinematics::getReducedSolution(iDynTree::Transform& baseTransformSolution, iDynTree::VectorDynSize& shapeSolution)

Parameters
baseTransformSolution out solution for the base position
shapeSolution out solution for the shape (the internal configurations)

Return the last solution of the inverse kinematics problem

This method returns in the shapeSolution variable only the joints that have been optimised viz. only the joints specified in the consideredJoints variable in the initialization

bool iDynTree::InverseKinematics::getReducedSolution(iDynTree::MatrixView<double> baseTransformSolution, iDynTree::Span<double> shapeSolution)

Parameters
baseTransformSolution out 4x4 homogeneous matrix solution for the base pose
shapeSolution out solution for the shape (the internal configurations)
Returns true if successful, false otherwise.

Return the last solution of the inverse kinematics problem

This method returns in the shapeSolution variable only the joints that have been optimised viz. only the joints specified in the consideredJoints variable in the initialization