Main Content

inverseKinematics

Create inverse kinematic solver

Description

TheinverseKinematicsSystem object™ creates an inverse kinematic (IK) solver to calculate joint configurations for a desired end-effector pose based on a specified rigid body tree model. Create a rigid body tree model for your robot using therigidBodyTreeclass. This model defines all the joint constraints that the solver enforces. If a solution is possible, the joint limits specified in the robot model are obeyed.

To specify more constraints besides the end-effector pose, including aiming constraints, position bounds, or orientation targets, consider usinggeneralizedInverseKinematics. This object allows you to compute multiconstraint IK solutions.

For closed-form analytical IK solutions, seeanalyticalInverseKinematics.

To compute joint configurations for a desired end-effector pose:

  1. Create theinverseKinematicsobject and set its properties.

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

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

Creation

Description

example

ik= inverseKinematicscreates an inverse kinematic solver. To use the solver, specify a rigid body tree model in theRigidBodyTreeproperty.

ik= inverseKinematics(Name,Value)creates an inverse kinematic solver with additional options specified by one or moreName,Valuepair arguments.Nameis a property name andValueis the corresponding value.Namemust appear inside single quotes (''). You can specify several name-value pair arguments in any order asName1,Value1,...,NameN,ValueN.

Properties

expand all

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

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

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

Rigid body tree model, specified as arigidBodyTreeobject. 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.

ik = inverseKinematics('RigidBodyTree',rigidbodytree)

Modify the rigid body tree model.

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

Reassign the rigid body tree to the IK solver. If the solver or thestepfunction is called before modifying the rigid body tree model, usereleaseto allow the property to be changed.

ik.RigidBodyTree = rigidbodytree;

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

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

Usage

Description

example

[configSol,solInfo] = ik(endeffector,pose,weights,initialguess)发现联合配置,达到规范ified end-effector pose. Specify an initial guess for the configuration and your desired weights on the tolerances for the six components ofpose. Solution information related to execution of the algorithm,solInfo, is returned with the joint configuration solution,configSol.

Input Arguments

expand all

End-effector name, specified as a character vector. The end effector must be a body on therigidBodyTreeobject specified in theinverseKinematicsSystem object.

End-effector pose, specified as a 4-by-4 homogeneous transform. This transform defines the desired position and orientation of the rigid body specified in theendeffectorproperty.

Weight for pose tolerances, specified as a six-element vector. The first three elements correspond to the weights on the error in orientation for the desired pose. The last three elements correspond to the weights on the error inxyzposition for the desired pose.

Initial guess of robot configuration, specified as a structure array or vector. Use this initial guess to help guide the solver to a desired robot configuration. The solution is not guaranteed to be close to this initial guess.

To use the vector form, set theDataFormatproperty of the object assigned in theRigidBodyTreeproperty to either'row'or'column'.

Output Arguments

expand all

Robot configuration, returned as a structure array. The structure array contains these fields:

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

  • JointPosition— Position of the corresponding joint

这个关节配置计算的解决方案that achieves the desired end-effector pose within the solution tolerance.

Note

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

To use the vector form, set theDataFormatproperty of the object assigned in theRigidBodyTreeproperty to either'row'or'column'.

Solution information, returned as a structure. The solution information structure contains these fields:

  • Iterations— Number of iterations run by the algorithm.

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

  • PoseErrorNorm— The magnitude of the pose error for the solution compared to the desired end-effector pose.

  • ExitFlag-代码算法前的更多细节ecution and what caused it to return. For the exit flags of each algorithm type, seeExit Flags.

  • Status— Character vector describing whether the solution is within the tolerance ('success') or the best possible solution the algorithm could find ('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 namedobj, use this syntax:

release(obj)

expand all

step RunSystem objectalgorithm
release Release resources and allow changes toSystem objectproperty values and input characteristics
reset Reset internal states ofSystem object

Examples

collapse all

Generate joint positions for a robot model to achieve a desired end-effector position. TheinverseKinematicssystem object uses inverse kinematic algorithms to solve for valid joint positions.

Load example robots. Thepuma1robot is arigidBodyTreemodel of a six-axis robot arm with six revolute joints.

loadexampleRobots.matshowdetails(puma1)
-------------------- Robot: (6 bodies) Idx Body Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 L1 jnt1 revolute base(0) L2(2) 2 L2 jnt2 revolute L1(1) L3(3) 3 L3 jnt3 revolute L2(2) L4(4) 4 L4 jnt4 revolute L3(3) L5(5) 5 L5 jnt5 revolute L4(4) L6(6) 6 L6 jnt6 revolute L5(5) --------------------

Generate a random configuration. Get the transformation from the end effector (L6) to the base for that random configuration. Use this transform as a goal pose of the end effector. Show this configuration.

randConfig = puma1.randomConfiguration; tform = getTransform(puma1,randConfig,'L6','base'); show(puma1,randConfig);

Figure contains an axes object. The axes object contains 13 objects of type patch, line. These objects represent base, L1, L2, L3, L4, L5, L6.

Create aninverseKinematicsobject for thepuma1model. Specify weights for the different components of the pose. Use a lower magnitude weight for the orientation angles than the position components. Use the home configuration of the robot as an initial guess.

ik = inverseKinematics('RigidBodyTree',puma1); weights = [0.25 0.25 0.25 1 1 1]; initialguess = puma1.homeConfiguration;

Calculate the joint positions using theikobject.

[configSoln,solnInfo] = ik('L6',tform,weights,initialguess);

Show the newly generated solution configuration. The solution is a slightly different joint configuration that achieves the same end-effector position. Multiple calls to theikobject can give similar or very different joint configurations.

show(puma1,configSoln);

Figure contains an axes object. The axes object contains 13 objects of type patch, line. These objects represent base, L1, L2, L3, L4, L5, L6.

References

[1] Badreddine, Hassan, Stefan Vandewalle, and Johan Meyers. "Sequential Quadratic Programming (SQP) for Optimal Control in Direct Numerical Simulation of Turbulent Flow."Journal of Computational Physics. 256 (2014): 1–16. doi:10.1016/j.jcp.2013.08.044.

[2] Bertsekas, Dimitri P.Nonlinear Programming. Belmont, MA: Athena Scientific, 1999.

[3] Goldfarb, Donald. "Extension of Davidon’s Variable Metric Method to Maximization Under Linear Inequality and Equality Constraints."SIAM Journal on Applied Mathematics. Vol. 17, No. 4 (1969): 739–64. doi:10.1137/0117067.

[4] Nocedal, Jorge, and Stephen Wright.Numerical Optimization. New York, NY: Springer, 2006.

[5] Sugihara, Tomomichi. "Solvability-Unconcerned Inverse Kinematics by the Levenberg–Marquardt Method."IEEE Transactions on RoboticsVol. 27, No. 5 (2011): 984–91. doi:10.1109/tro.2011.2148230.

[6] Zhao, Jianmin, and Norman I. Badler. "Inverse Kinematics Positioning Using Nonlinear Programming for Highly Articulated Figures."ACM Transactions on GraphicsVol. 13, No. 4 (1994): 313–36. doi:10.1145/195826.195827.

Extended Capabilities

Version History

Introduced in R2016b

expand all

Behavior change in future release