getInverseKinematics (getIK) calculates positions for a
desired end effector pose.
This method computes the joint positions associated to a
desired end-effector configuration. The end effector is
assumed to be the last body in the kinematic chain.
getInverseKinematics uses a gradient-descent based local
optimizer to find a valid configuration.
'InitialPositions' ('Initial') provides the seed for the
numerical optimization. IT IS HIGHLY RECOMMENDED THAT YOU
SPECIFY SEED POSITIONS, AND A FUTURE VERSION OF THE API
WILL MAKE THIS A REQUIRED PARAMETER.
There are a variety of optimization criteria that can be
combined depending on the application. Available parameters
include:
Parameter EndEffector Target Size / Units
'XYZ' xyz position in [m] 3x1 in [m]
'TipAxis' z-axis orientation 3x1 unit vector
of the last body in
in chain [unit vector]
'SO3' 3-DoF orientation 3x3 rotation
matrix
Note that 'XYZ' supports NaN for dimensions that
should be ignored. For example, a planar arm may use
the target position of [x y NaN].
All target positions and orientations are expressed in
the base frame.
'MaxIterations' ('MaxIter') sets the maximum allowed
iterations of the numerical optimization before returning.
This can prevent IK from taking a long time to run, at the
expense of solutions that are potentially less accurate.
The default value is 150 iterations.
Examples:
% Inverse kinematics for a 3-DoF arm, specifying initial
% joint angle positions.
xyz = [0.2 0.1 0.0];
initialJointAngs = [0 -pi/4 pi/2];
waypoints = kin.getInverseKinematics( 'XYZ', xyz, ...
'IntialPositions', initialJointAngs );
% Inverse kinematics for a 5-DoF arm, specifying initial
% joint angle positions.
xyz = [0.2 0.1 0.0];
tipAxis = [0 0 -1]; % end effector points straight down
initialJointAngs = [0 -pi/4 pi/2 pi/4 0];
waypoints = kin.getIK( 'XYZ', xyz, ...
'TipAxis', tipAxis, ...
'initial', initialJointAngs );
% Inverse kinematics for full 6-DoF arm, using the
% latest feedback as the seed position for IK.
xyz = [0.3 -0.1 0.2];
rotMatrix = eye(3);
fbk = group.getNextFeedback();
positions = kin.getIK( 'XYZ', xyz, ...
'SO3', rotMatrix, ...
'initial', fbk.position );