Main Content

analyticalInverseKinematics

Solve closed-form inverse kinematics

Since R2020b

Description

The analyticalInverseKinematics object generates functions that computes all closed-form solutions for inverse kinematics (IK) for serial-chain manipulators using an approach based on the Pieper method [1]. The object generates a custom function to find multiple distinct joint configurations that achieve the desired end-effector pose for a kinematic group of a rigid body tree robot model given that the specified kinematic group represents an applicable six-DOF serial manipulator with a wrist and compatible kinematic parameters. A wrist is defined as three consecutive revolute joints with orthogonal axes.

These are the key elements of the solver:

  • Robot model — Rigid body tree model that defines the kinematics of the robot. Specify this model as a rigidBodyTree object when creating the solver.

  • Kinematic group — Base and end-effector body names for a six-DOF serial chain that is part of the robot model. To set this parameter, use the showdetails function.

  • Kinematic group type — Classification of joints connecting base to end effector.

To see all possible supported kinematic groups for your robot, use the showdetails object function. To set a specific group from the list, click the Use this kinematic group link for a kinematic group in the returned list.

To calculate inverse kinematics for a specific kinematic group, use the generateIKFunction object function. To ensure your robot model and kinematic group are compatible, check the IsValidGroupForIK property after selecting a kinematic group.

To generate numeric solutions, use the inverseKinematics and generalizedInverseKinematics objects.

Creation

Description

example

analyticalIK = analyticalInverseKinematics(robotRBT) creates an analytical inverse kinematics solver for a rigid body tree robot model, specified as a rigidBodyTree object. The end effector is the final body listed in the Bodies property of the robot model. The robotRBT argument sets the RigidBodyTree property.

analyticalIK = analyticalInverseKinematics(robotRBT,'KinematicGroup',kinGroup) sets the KinematicGroup property to the kinGroup argument, specified as a structure.

Properties

expand all

Rigid body tree robot model, specified as a rigidBodyTree object. To use a provided robot model, see loadrobot. To import Unified Robot Description Format (URDF) models, see the importrobot function.

Base and end-effector body names, specified as a structure. The structure contains these fields:

  • BaseName — Name of the body in the robot model stored in the RigidBodyTree property that represents the base of the kinematic group. The default value is the base of the RigidBodyTree property.

  • EndEffectorBodyName — Name of the body in the robot model stored in the RigidBodyTree property that represents the end of the kinematic group. The default value is the last body in the Bodies property of the robot model.

A valid kinematic group must represent a six-DOF serial chain with a wrist and a contain joint types defined by KinematicGroupType as 'XXXSSS'. A wrist is defined as three consecutive revolute joints with orthogonal axes with compatible kinematic parameters and is represented as SSS. XXX is either three revolute joints RRR or another wrist SSS. If the kinematic group type contains a prismatic joint, P, the kinematic group is invalid for use with this solver. To check if your kinematic group is valid for this solver, see the IsValidGroupForIK property.

When created, the object automatically selects a kinematic group from the robot model, but other options may be available. To see valid kinematic groups for your model, use the showdetails object function.

Example: struct("BaseName","base","EndEffectoryBodyName","tool0")

Data Types: struct

This property is read-only.

Classification of the kinematic group, stored as a character vector. Each character specifies the joint type of each rigid body from the base to the end effector of the kinematic group. These are the options for the characters:

  • R — Revolute joint that does not form a wrist

  • P — Prismatic joint

  • S — Revolute joint of a wrist

    Note

    A wrist or spherical joint is comprised of three consecutive revolute joints with orthogonal axes.

To qualify as a valid kinematic group for the analyticalInverseKinematics object, the kinematic group type must be 'XXXSSS', where XXX can be either RRR or SSS. If the kinematic group type contains a prismatic joint, P, the kinematic group is invalid for use with this solver. To check if your kinematic group is valid for this solver, see the IsValidGroupForIK property.

When created, the object automatically selects a kinematic group from the robot model, but other options may be available. To see valid kinematic groups for your model, use the showdetails object function.

Example: 'RRRSSS'

Data Types: char

This property is read-only.

Mapping of IK solution configuration to rigid body tree configuration, specified as a six-element vector. This mapping converts the indices of the IK solution that is output from the generateIKFunction function to the indices for the robot model stored in the RigidBodyTree property.

Example: [1 2 3 4 5 6]

Data Types: double

This property is read-only.

Indication of whether a closed-form solution is possible, stored as a logical, 1 (true or 0 (false). When this property is false, the generateIKFunction function cannot generate an IK solver for the current kinematic group. Use the showdetails object function to check if any valid groups exist. To select a valid group, specify a different base or end effector to the KinematicGroup property, or change kinematic parameters of your robot model stored in the RigidBodyTree property.

To qualify as a valid kinematic group for the analyticalInverseKinematics object, the kinematic group type must be 'XXXSSS', where XXX can be either RRR or SSS. If the kinematic group type contains a prismatic joint, P, the kinematic group is invalid for use with this solver. To check if your kinematic group is valid for this solver, see the IsValidGroupForIK property.

Data Types: logical

Object Functions

generateIKFunctionGenerate function for closed-form inverse kinematics
showdetailsDisplay overview of available kinematic groups

Examples

collapse all

Generate closed-form inverse kinematics (IK) solutions for a desired end effector. Load the provided robot model and inspect details about the feasible kinematic groups of base and end-effector bodies. Generate a function for your desired kinematic group. Inspect the various configurations for a specific end-effector pose.

Robot Model

Load the ABB IRB 120 robot model into the workspace. Display the model.

robot = loadrobot('abbIrb120','DataFormat','row');
show(robot);

Analytical IK

Create the analytical IK solver. Show details for the robot model, which lists the different kinematic groups available for closed-form analytical IK solutions. Select the second kinematic group by clicking the Use this kinematic group link in the second row of the table.

aik = analyticalInverseKinematics(robot);
showdetails(aik)
--------------------
Robot: (8 bodies)

Index      Base Name   EE Body Name     Type                    Actions
-----      ---------   ------------     ----                    -------
    1      base_link         link_6   RRRSSS   Use this kinematic group
    2      base_link          tool0   RRRSSS   Use this kinematic group

Inspect the kinematic group, which lists the base and end-effector body names. For this robot, the group uses the 'base_link' and 'tool0' bodies, respectively.

aik.KinematicGroup
ans = struct with fields:
               BaseName: 'base_link'
    EndEffectorBodyName: 'tool0'

Generate Function

Generate the IK function for the selected kinematic group. Specify a name for the function, which is generated and saved in the current directory.

generateIKFunction(aik,'robotIK');

Specify a desired end-effector position. Convert the xyz-position to a homogeneous transformation.

eePosition = [0 0.5 0.5];
eePose = trvec2tform(eePosition);
hold on
plotTransforms(eePosition,tform2quat(eePose))
hold off

Generate Configuration for IK Solution

Specify the homogeneous transformation to the generated IK function, which generates all solutions for the desired end-effector pose. Display the first generated configuration to verify that the desired pose has been achieved.

ikConfig = robotIK(eePose); % Uses the generated file

show(robot,ikConfig(1,:));
hold on
plotTransforms(eePosition,tform2quat(eePose))
hold off

Display all of the closed-form IK solutions sequentially.

figure;
numSolutions = size(ikConfig,1);

for i = 1:size(ikConfig,1)
    subplot(1,numSolutions,i)
    show(robot,ikConfig(i,:));
end

Some manipulator robot models have large degrees-of-freedom (DOFs). To reach certain end-effector poses, however, only six DOFs are required. Use the analyticalInverseKinematics object, which supports six-DOF robots, to determine various valid kinematic groups for this large-DOF robot model. Use the showdetails object function to get information about the model.

Load Robot Model and Generate IK Solver

Load the robot model into the workspace, and create an analyicalInverseKinematics object. Use the showdetails object function to see the supported kinematic groups.

robot = loadrobot('willowgaragePR2','DataFormat','row');
aik = analyticalInverseKinematics(robot);
opts = showdetails(aik);
--------------------
Robot: (94 bodies)

Index                                          Base Name                                       EE Body Name     Type                    Actions
-----                                          ---------                                       ------------     ----                    -------
    1                                l_shoulder_pan_link                                  l_wrist_roll_link   RSSSSS   Use this kinematic group
    2                                r_shoulder_pan_link                                  r_wrist_roll_link   RSSSSS   Use this kinematic group
    3                                l_shoulder_pan_link                                l_gripper_palm_link   RSSSSS   Use this kinematic group
    4                                r_shoulder_pan_link                                r_gripper_palm_link   RSSSSS   Use this kinematic group
    5                                l_shoulder_pan_link                                l_gripper_led_frame   RSSSSS   Use this kinematic group
    6                                l_shoulder_pan_link                 l_gripper_motor_accelerometer_link   RSSSSS   Use this kinematic group
    7                                l_shoulder_pan_link                               l_gripper_tool_frame   RSSSSS   Use this kinematic group
    8                                r_shoulder_pan_link                                r_gripper_led_frame   RSSSSS   Use this kinematic group
    9                                r_shoulder_pan_link                 r_gripper_motor_accelerometer_link   RSSSSS   Use this kinematic group
   10                                r_shoulder_pan_link                               r_gripper_tool_frame   RSSSSS   Use this kinematic group

Select a group programmatically using the output of the showdetails object function, opts. The selected group uses the left shoulder as the base with the left wrist as the end effector.

aik.KinematicGroup = opts(1).KinematicGroup;
disp(aik.KinematicGroup)
               BaseName: 'l_shoulder_pan_link'
    EndEffectorBodyName: 'l_wrist_roll_link'

Generate the IK function for the selected group.

generateIKFunction(aik,'willowRobotIK');

Solve Analytical IK

Define a target end-effector pose using a randomly-generated configuration.

rng(0);
expConfig = randomConfiguration(robot);

eeBodyName = aik.KinematicGroup.EndEffectorBodyName;
baseName = aik.KinematicGroup.BaseName;
expEEPose = getTransform(robot,expConfig,eeBodyName,baseName);

Solve for all robot configurations that achieve the defined end-effector pose using the generated IK function. To ignore joint limits, specify false as the second input argument.

ikConfig = willowRobotIK(expEEPose,false);

To display the target end-effector pose in the world frame, get the transformation from the base of the robot model, rather than the base of the kinematic group. Display all of the generated IK solutions by specifying the indices for your kinematic group IK solution in the configuration vector used with the show function.

eeWorldPose = getTransform(robot,expConfig,eeBodyName);

generatedConfig = repmat(expConfig, size(ikConfig,1), 1);
generatedConfig(:,aik.KinematicGroupConfigIdx) = ikConfig;

for i = 1:size(ikConfig,1)
    figure;
    ax = show(robot,generatedConfig(i,:));
    hold all;
    plotTransforms(tform2trvec(eeWorldPose),tform2quat(eeWorldPose),'Parent',ax);
    title(['Solution ' num2str(i)]);
end

References

[1] Pieper, Donald. The Kinematics of Manipulators Under Computer Control. Stanford University, 1968.

Extended Capabilities

Version History

Introduced in R2020b