rt_ikine560 - compute the inverse kinematics for a Puma 560 like robot arm[view code]
"l" | left-handed (lefty) solution (default) |
"r" | right-handed (righty) solution |
"u" | elbow up solution (default) |
"d" | elbow down solution |
"f" | wrist flipped solution (default) |
"n" | wrist not flipped solution |
This function returns the joint coordinates corresponding to the end-effector homogeneous transform T. It is computed using a symbolic solution appropriate for Puma 560 like robots, that is, all revolute 6DOF arms, with a spherical wrist. The use of a symbolic solution means that it executes over 50 times faster than rt_ikine for a Puma 560 solution.
A further advantage is that rt_ikine560 allows control over the specified solution returned by using the string config.
// To show how the IKP (Inverse Kinematic Problem) for a Puma 560 can // be solved, the following code could be used. // load Puma 560 parameters exec <PATH>/models/rt_puma560.sce; // end-effector location for a generic joint state vector q = [0.2, -1.35, 0.65, 0, 1.4, 2.55], T06 = rt_fkine(p560, q), // solve the IKP Q1 = rt_ikine560(p560, T06, "rd"), // ELBOW DOWN, SHOULDER FORE Q2 = rt_ikine560(p560, T06, "ru"), // ELBOW UP, SHOULDER FORE Q3 = rt_ikine560(p560, T06, "ld"), // ELBOW DOWN, SHOULDER AFT Q4 = rt_ikine560(p560, T06, "lu"), // ELBOW UP, SHOULDER AFT // test solutions T06 - rt_fkine(p560, Q1), T06 - rt_fkine(p560, Q2), T06 - rt_fkine(p560, Q3), T06 - rt_fkine(p560, Q4), // The same solutions can be obtained in a more straightforward manner: Q = rt_ikine560paul(p560, T06); // Solve an IKP for a Puma 560 robot when the joint state vector has // q5 belonging to (-%pi, 0) radians q = [0.2, -1.35, 0.65, 0, -1.4, 2.55], // q5 in (-%pi, 0) T06 = rt_fkine(p560, q), Q1 = rt_ikine560(p560, T06, "rdn"), // Q1 == q Q = rt_ikine560paul(p560, T06), // Q(1,4:6) is different from // q(4:6), however you should // know that they are // equivalent in their effects // Solve an IKP for a Puma 560 robot when the joint state vector is // a singular configuration for the robot p560_2 = rt_robot(p560); // robot copy p560_2.name = "Puma 560 (2)"; L = p560_2.links; L(3).A = 0; // Puma 560 without.. L(3).D = 0; // ..shoulder offset q = [0, 0.3926991, %pi/4, 0, 0.2, 1]; // shoulder-singular config. T06 = rt_fkine(p560_2, q), // compute end-effector location Q = rt_ikine560(p560_2, T06, "lu"), // no warning displayed Q = rt_ikine560paul(p560_2, T06), // warns you about singularity
Note that the dimensional units for the last column of the T matrix must agree with the dimensional units used in the robot object robot. The units can be whatever you choose (metres, inches, cubits or furlongs) but they must be consistent. The toolbox definitions rt_puma560 and rt_stanford all use SI units with dimensions in metres.
This function will not work for robot objects that use the modified Denavit-Hartenberg convention.
rt_ikine, rt_ikine560paul, rt_ikinestanfpaul, rt_fkine, rt_robot, robot/rt_plot,
Corke, P.I. "A Robotics Toolbox for MATLAB", IEEE Robotics and Automation Magazine, Volume 3(1), March 1996, pp. 24-32
R. P. Paul and H. Zhang, "Computationally efficient kinematics for manipulators with spherical wrists", Int. J. Robot. Res., vol 5, no. 2, pp. 32-44, 1986.