%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Q = INVERSEKINEMATIC_PUMA560(robot, T) Solves the inverse kinematic problem for the UNIMATE PUMA 560 robot where: robot stores the robot parameters. T is an homogeneous transform that specifies the position/orientation of the end effector. A call to Q=INVERSEKINEMATIC_PUMA560 returns 8 possible solutions, thus, Q is a 6x8 matrix where each column stores 6 feasible joint values. Example code: robot=load_robot('UNIMATE', 'puma560'); q = [0 0 0 0 0 0]; T = directkinematic(robot, q); %Call the inversekinematic for this robot qinv = inversekinematic(robot, T); check that all of them are feasible solutions! and every Ti equals T for i=1:8, Ti = directkinematic(robot, qinv(:,i)) end See also DIRECTKINEMATIC. %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0002 % Q = INVERSEKINEMATIC_PUMA560(robot, T) 0003 % Solves the inverse kinematic problem for the UNIMATE PUMA 560 robot 0004 % where: 0005 % robot stores the robot parameters. 0006 % T is an homogeneous transform that specifies the position/orientation 0007 % of the end effector. 0008 % 0009 % A call to Q=INVERSEKINEMATIC_PUMA560 returns 8 possible solutions, thus, 0010 % Q is a 6x8 matrix where each column stores 6 feasible joint values. 0011 % 0012 % 0013 % Example code: 0014 % 0015 % robot=load_robot('UNIMATE', 'puma560'); 0016 % q = [0 0 0 0 0 0]; 0017 % T = directkinematic(robot, q); 0018 % %Call the inversekinematic for this robot 0019 % qinv = inversekinematic(robot, T); 0020 % check that all of them are feasible solutions! 0021 % and every Ti equals T 0022 % for i=1:8, 0023 % Ti = directkinematic(robot, qinv(:,i)) 0024 % end 0025 % See also DIRECTKINEMATIC. 0026 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0027 0028 % Copyright (C) 2012, by Arturo Gil Aparicio 0029 % 0030 % This file is part of ARTE (A Robotics Toolbox for Education). 0031 % 0032 % ARTE is free software: you can redistribute it and/or modify 0033 % it under the terms of the GNU Lesser General Public License as published by 0034 % the Free Software Foundation, either version 3 of the License, or 0035 % (at your option) any later version. 0036 % 0037 % ARTE is distributed in the hope that it will be useful, 0038 % but WITHOUT ANY WARRANTY; without even the implied warranty of 0039 % MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 0040 % GNU Lesser General Public License for more details. 0041 % 0042 % You should have received a copy of the GNU Leser General Public License 0043 % along with ARTE. If not, see <http://www.gnu.org/licenses/>. 0044 function q = inversekinematic_puma560(robot, T) 0045 0046 %initialize q, 0047 %eight possible solutions are generally feasible 0048 q=zeros(6,8); 0049 0050 %Evaluate the parameters 0051 d = eval(robot.DH.d); 0052 0053 %See geometry at the reference for this robot 0054 L6=d(6); 0055 0056 %this is the first shift in the arm, aprox 5.5 inches. 0057 shift1 = d(3); 0058 0059 %T= [ nx ox ax Px; 0060 % ny oy ay Py; 0061 % nz oz az Pz]; 0062 Px=T(1,4); 0063 Py=T(2,4); 0064 Pz=T(3,4); 0065 0066 %Compute the position of the wrist, being W the Z component of the end effector's system 0067 W = T(1:3,3); 0068 0069 % Pm: wrist position 0070 Pm = [Px Py Pz]' - L6*W; 0071 0072 %first joint, two possible solutions admited: 0073 beta = atan2(Pm(1), -Pm(2)); 0074 0075 hyp = sqrt(Pm(1)^2+Pm(2)^2); 0076 eta = acos(shift1/hyp); 0077 0078 %two possible solutions exist, q1, and q1+2*eta 0079 q1=beta-eta; 0080 0081 %solve for q2 0082 q2_1=solve_for_theta2(robot, [q1 0 0 0 0 0 0], Pm); 0083 0084 q2_2=solve_for_theta2(robot, [q1+2*eta 0 0 0 0 0 0], Pm); 0085 0086 %solve for q3 0087 q3_1=solve_for_theta3(robot, [q1 0 0 0 0 0 0], Pm); 0088 0089 q3_2=solve_for_theta3(robot, [q1+2*eta 0 0 0 0 0 0], Pm); 0090 0091 0092 %the next matrix doubles each column. For each two columns, two different 0093 %configurations for theta4, theta5 and theta6 will be computed. These 0094 %configurations are generally referred as wrist up and wrist down solution 0095 q = [q1 q1 q1 q1 q1+2*eta q1+2*eta q1+2*eta q1+2*eta; 0096 q2_1(1) q2_1(1) q2_1(2) q2_1(2) q2_2(1) q2_2(1) q2_2(2) q2_2(2); 0097 q3_1(1) q3_1(1) q3_1(2) q3_1(2) q3_2(1) q3_2(1) q3_2(2) q3_2(2); 0098 0 0 0 0 0 0 0 0; 0099 0 0 0 0 0 0 0 0; 0100 0 0 0 0 0 0 0 0]; 0101 0102 %leave only the real part of the solutions 0103 q=real(q); 0104 0105 %Note that in this robot, the joint q3 has a non-simmetrical range. In this 0106 %case, the joint ranges from 60 deg to -219 deg, thus, the typical normalizing 0107 %step is avoided in this angle (the next line is commented). When solving 0108 %for the orientation, the solutions are normalized to the [-pi, pi] range 0109 %only for the theta4, theta5 and theta6 joints. 0110 0111 %normalize q to [-pi, pi] 0112 q(1,:) = normalize(q(1,:)); 0113 q(2,:) = normalize(q(2,:)); 0114 % solve for the last three joints 0115 % for any of the possible combinations (theta1, theta2, theta3) 0116 for i=1:2:size(q,2), 0117 qtemp = solve_spherical_wrist(robot, q(:,i), T, 1,'geometric'); %wrist up 0118 qtemp(4:6)=normalize(qtemp(4:6)); 0119 q(:,i)=qtemp; 0120 0121 qtemp = solve_spherical_wrist(robot, q(:,i), T, -1, 'geometric'); %wrist up 0122 qtemp(4:6)=normalize(qtemp(4:6)); 0123 q(:,i+1)=qtemp; 0124 end 0125 0126 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0127 % solve for second joint theta2, two different 0128 % solutions are returned, corresponding 0129 % to elbow up and down solution 0130 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0131 function q2 = solve_for_theta2(robot, q, Pm) 0132 0133 %Evaluate the parameters 0134 d = eval(robot.DH.d); 0135 a = eval(robot.DH.a); 0136 0137 %See geometry 0138 L2=a(2); 0139 L3=d(4); 0140 A2=a(3); 0141 0142 %See geometry of the robot 0143 %compute L4 0144 L4 = sqrt(A2^2 + L3^2); 0145 0146 %given q1 is known, compute first DH transformation 0147 T01=dh(robot, q, 1); 0148 0149 %Express Pm in the reference system 1, for convenience 0150 p1 = inv(T01)*[Pm; 1]; 0151 0152 r = sqrt(p1(1)^2 + p1(2)^2); 0153 0154 beta = atan2(p1(2), p1(1)); 0155 gamma = real(acos((L2^2+r^2-L4^2)/(2*r*L2))); 0156 0157 %return two possible solutions 0158 %elbow up and elbow down 0159 %the order here is important and is coordinated with the function 0160 %solve_for_theta3 0161 q2(1) = beta + gamma; %elbow up 0162 q2(2) = beta - gamma; %elbow down 0163 0164 0165 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0166 % solve for third joint theta3, two different 0167 % solutions are returned, corresponding 0168 % to elbow up and down solution 0169 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0170 function q3 = solve_for_theta3(robot, q, Pm) 0171 0172 %Evaluate the parameters 0173 d = eval(robot.DH.d); 0174 a = eval(robot.DH.a); 0175 0176 %See geometry 0177 L2=a(2); 0178 L3=d(4); 0179 A2=a(3); 0180 0181 %See geometry of the robot 0182 %compute L4 0183 L4 = sqrt(A2^2 + L3^2); 0184 0185 %the angle phi is fixed 0186 phi=acos((A2^2+L4^2-L3^2)/(2*A2*L4)); 0187 0188 %given q1 is known, compute first DH transformation 0189 T01=dh(robot, q, 1); 0190 0191 %Express Pm in the reference system 1, for convenience 0192 p1 = inv(T01)*[Pm; 1]; 0193 0194 r = sqrt(p1(1)^2 + p1(2)^2); 0195 0196 eta = real(acos((L2^2 + L4^2 - r^2)/(2*L2*L4))); 0197 0198 %return two possible solutions 0199 %elbow up and elbow down solutions 0200 %the order here is important 0201 q3(1) = pi - phi+ eta; 0202 q3(2) = pi - phi - eta; 0203 0204