Main Content

generalizedInverseKinematics

Create multiconstraint inverse kinematics solver

Description

The generalizedInverseKinematics System object™ uses a set of kinematic constraints to compute a joint configuration for the rigid body tree model specified by a rigidBodyTree object. The generalizedInverseKinematics object uses a nonlinear solver to satisfy the constraints or reach the best approximation.

Specify the constraint types, ConstraintInputs, before calling the object. To change constraint inputs after calling the object, call release(gik).

Specify the constraint inputs as constraint objects and call generalizedInverseKinematics with these objects passed into it. To create constraint objects, use the following objects:

If your only constraint is the end-effector position and orientation, consider using inverseKinematics as your solver instead.

For closed-form analytical inverse kinematics solutions, see analyticalInverseKinematics.

To solve the generalized inverse kinematics constraints:

  1. Create the generalizedInverseKinematics object and set its properties.

  2. Call the object with arguments, as if it were a function.

To learn more about how System objects work, see What Are System Objects?

Creation

Description

example

gik = generalizedInverseKinematics returns a generalized inverse kinematics solver with no rigid body tree model specified. Specify a rigidBodyTree model and the ConstraintInputs property before using this solver.

gik = generalizedInverseKinematics('RigidBodyTree',rigidbodytree,'ConstraintInputs',inputTypes) returns a generalized inverse kinematics solver with the rigid body tree model and the expected constraint inputs specified.

gik = generalizedInverseKinematics(Name,Value) returns a generalized inverse kinematics solver with each specified property name set to the specified value by one or more Name,Value pair arguments. Name must appear inside single quotes (''). You can specify several name-value pair arguments in any order as Name1,Value1,...,NameN,ValueN.

Properties

expand all

Unless otherwise indicated, properties are nontunable, which means you cannot change their values after calling the object. Objects lock when you call them, and the release function unlocks them.

If a property is tunable, you can change its value at any time.

For more information on changing property values, see System Design in MATLAB Using System Objects.

This property is read-only.

Number of constraint inputs, specified as a scalar. The value of this property is the number of constraint types specified in the ConstraintInputs property.

Constraint input types, specified as a cell array of character vectors. The possible constraint input types with their associated constraint objects are:

There are also closed-loop joint constraints that constrain two rigid bodies such that the constrained motion is similar to that of an additional joint between the two bodies. Their constraint input types with their associated constraint objects are:

Use the constraint objects to specify the required parameters and pass those object types into the object when you call it. For example:

Create the generalized inverse kinematics solver object. Specify the RigidBodyTree and ConstraintInputs properties.

gik = generalizedInverseKinematics(...
					'RigidBodyTree',rigidbodytree,
					'ConstraintInputs',{'position','aiming'});

Create the corresponding constraint objects.

positionTgt = constraintPositionTarget('left_palm');
aimConst = constraintAiming('right_palm');

Pass the constraint objects into the solver object with an initial guess.

configSol = gik(initialGuess,positionTgt,aimConst);

Rigid body tree model, specified as a rigidBodyTree object. Define this property before using the solver. If you modify your rigid body tree model, reassign the rigid body tree to this property. For example:

Create IK solver and specify the rigid body tree.

gik = generalizedInverseKinematics(...
					'RigidBodyTree',rigidbodytree,
					'ConstraintInputs',{'position','aiming'});

Modify the rigid body tree model.

addBody(rigidbodytree,rigidBody('body1'),'base')

Reassign the rigid body tree to the IK solver. If the solver or the step function is called before modifying the rigid body tree model, use release to allow the property to be changed.

gik.RigidBodyTree = rigidbodytree;

Algorithm for solving inverse kinematics, specified as either 'BFGSGradientProjection' or 'LevenbergMarquardt'. For details of each algorithm, see Inverse Kinematics Algorithms.

Parameters associated with the specified algorithm, specified as a structure. The fields in the structure are specific to the algorithm. See Solver Parameters.

Usage

Description

[configSol,solInfo] = gik(initialguess,constraintObj,...,constraintObjN) finds a joint configuration, configSol, based on the initial guess and a comma-separated list of constraint description objects. The number of constraint descriptions depends on the ConstraintInputs property.

Input Arguments

expand all

Initial guess of robot configuration, specified as a structure array or vector. The value of initialguess depends on the DataFormat property of the object specified in the RigidBodyTree property specified in gik.

Use this initial guess to guide the solver to the target robot configuration. However, the solution is not guaranteed to be close to this initial guess.

Constraint descriptions defined by the ConstraintInputs property of gik, specified as one or more of these constraint objects:

Output Arguments

expand all

Robot configuration solution, returned as a structure array or vector, depends on the DataFormat property of the object specified in the RigidBodyTree property specified in gik.

The structure array contains these fields:

  • JointName — Character vector for the name of the joint specified in the RigidBodyTree robot model

  • JointPosition — Position of the corresponding joint

The vector output is an array of the joint positions that would be given in JointPosition for a structure output.

This joint configuration is the computed solution that achieves the target end-effector pose within the solution tolerance.

Note

For revolute joints, if the joint limits exceed a range of 2*pi, where joint position wrapping occurs, then the returned joint position is the one closest to the joint's lower bound.

Solution information, returned as a structure containing these fields:

  • Iterations — Number of iterations run by the solver.

  • NumRandomRestarts — Number of random restarts because the solver got stuck in a local minimum.

  • ConstraintViolation — Information about the constraint, returned as a structure array. Each structure in the array has these fields:

    • Type: Type of the corresponding constraint input, as specified in the ConstraintInputs property.

    • Violation: Vector of constraint violations for the corresponding constraint type. 0 indicates that the constraint is satisfied.

  • ExitFlag — Code that gives more details on the solver execution and what caused it to return. For the exit flags of each solver type, see Exit Flags.

  • Status — Character vector describing whether the solution is within the tolerances defined by each constraint ('success'). If the solution is outside the tolerance, the best possible solution that the solver could find is given ('best available').

Object Functions

To use an object function, specify the System object as the first input argument. For example, to release system resources of a System object named obj, use this syntax:

release(obj)

expand all

stepRun System object algorithm
releaseRelease resources and allow changes to System object property values and input characteristics
resetReset internal states of System object

Examples

collapse all

Create a generalized inverse kinematics solver that holds a robotic arm at a specific location and points toward the robot base. Create the constraint objects to pass the necessary constraint parameters into the solver.

Load KUKA iiwa 14 robot model from the Robotics System Toolbox™ loadrobot, returned as a rigidBodyTree object.

manipulator = loadrobot("kukaIiwa14");

Create the System object™ for solving generalized inverse kinematics.

gik = generalizedInverseKinematics;

Configure the System object to use the KUKA LBR robot.

gik.RigidBodyTree = manipulator;

Tell the solver to expect a constraintAiming and constraintPositionTarget object as the constraint inputs.

gik.ConstraintInputs = {"position","aiming"};

Create the two constraint objects.

  1. The origin of the body named iiwa_link_ee_kuka is located at [0.0 0.5 0.5] relative to the robot's base frame.

  2. The z-axis of the body named iiwa_link_ee_kuka points toward the origin of the robot's base frame.

posTgt = constraintPositionTarget("iiwa_link_ee_kuka");
posTgt.TargetPosition = [0.0 0.5 0.5];

aimCon = constraintAiming("iiwa_link_ee_kuka");
aimCon.TargetPoint = [0.0 0.0 0.0];

Find a configuration that satisfies the constraints. You must pass the constraint objects into the System object in the order in which they were specified in the ConstraintInputs property. Specify an initial guess at the robot configuration.

q0 = homeConfiguration(manipulator); % Initial guess for solver
[q,solutionInfo] = gik(q0,posTgt,aimCon);

Visualize the configuration returned by the solver.

show(manipulator,q);
title(sprintf("Solver status: %s", solutionInfo.Status))
axis([-0.75 0.75 -0.75 0.75 -0.5 1])

Plot a line segment from the target position to the origin of the base. The origin of the tool0 frame coincides with one end of the segment, and its z-axis is aligned with the segment.

hold on
plot3([0.0 0.0],[0.5 0.0],[0.5 0.0],"--o")
hold off

Extended Capabilities

Version History

Introduced in R2017a

expand all