%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Q = INVERSEKINEMATIC_IRB6650S_90_390(robot, T) Solves the inverse kinematic problem for the ABB IRB IRB6650-90/390 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_IRBS6650_90_390 returns 8 possible solutions, thus, Q is a 6x8 matrix where each column stores 6 feasible joint values. Example code: abb=load_robot('ABB', 'IRB6650S_90_390'); q = [0 0 0 0 0 0]; T = directkinematic(abb, q); %Call the inversekinematic for this robot qinv = inversekinematic(abb, T); check that all of them are feasible solutions! and every Ti equals T for i=1:8, Ti = directkinematic(abb, qinv(:,i)) end See also DIRECTKINEMATIC. Author: Arturo Gil Aparicio Universitas Miguel Hernandez, SPAIN. %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0002 % Q = INVERSEKINEMATIC_IRB6650S_90_390(robot, T) 0003 % Solves the inverse kinematic problem for the ABB IRB IRB6650-90/390 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_IRBS6650_90_390 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 % abb=load_robot('ABB', 'IRB6650S_90_390'); 0016 % q = [0 0 0 0 0 0]; 0017 % T = directkinematic(abb, q); 0018 % %Call the inversekinematic for this robot 0019 % qinv = inversekinematic(abb, T); 0020 % check that all of them are feasible solutions! 0021 % and every Ti equals T 0022 % for i=1:8, 0023 % Ti = directkinematic(abb, qinv(:,i)) 0024 % end 0025 % See also DIRECTKINEMATIC. 0026 % 0027 % Author: Arturo Gil Aparicio 0028 % Universitas Miguel Hernandez, SPAIN. 0029 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0030 0031 % Copyright (C) 2012, by Arturo Gil Aparicio 0032 % 0033 % This file is part of ARTE (A Robotics Toolbox for Education). 0034 % 0035 % ARTE is free software: you can redistribute it and/or modify 0036 % it under the terms of the GNU Lesser General Public License as published by 0037 % the Free Software Foundation, either version 3 of the License, or 0038 % (at your option) any later version. 0039 % 0040 % ARTE is distributed in the hope that it will be useful, 0041 % but WITHOUT ANY WARRANTY; without even the implied warranty of 0042 % MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 0043 % GNU Lesser General Public License for more details. 0044 % 0045 % You should have received a copy of the GNU Leser General Public License 0046 % along with ARTE. If not, see <http://www.gnu.org/licenses/>. 0047 function q = inversekinematic_irb6650S_90_390(robot, T) 0048 0049 %initialize q, 0050 %eight possible solutions are generally feasible 0051 q=zeros(6,8); 0052 0053 % %Evaluate the parameters 0054 % theta = eval(robot.DH.theta); 0055 d = eval(robot.DH.d); 0056 L6=d(6); 0057 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 % if q(1) is a solution, then q(1) + pi is also a solution 0074 q1=atan2(Pm(2), Pm(1)); 0075 0076 0077 %solve for q2 0078 q2_1=solve_for_theta2(robot, [q1 0 0 0 0 0 0], Pm); 0079 %the other possible solution is q1 + pi 0080 q2_2=solve_for_theta2(robot, [q1+pi 0 0 0 0 0 0], Pm); 0081 0082 %solve for q3 0083 q3_1=solve_for_theta3(robot, [q1 0 0 0 0 0 0], Pm); 0084 %solver for q3 for both cases 0085 q3_2=solve_for_theta3(robot, [q1+pi 0 0 0 0 0 0], Pm); 0086 0087 0088 %the next matrix doubles each column. For each two columns, two different 0089 %configurations for theta4, theta5 and theta6 will be computed. These 0090 %configurations are generally referred as wrist up and wrist down solution 0091 q = [q1 q1 q1 q1 q1+pi q1+pi q1+pi q1+pi; 0092 q2_1(1) q2_1(1) q2_1(2) q2_1(2) q2_2(1) q2_2(1) q2_2(2) q2_2(2); 0093 q3_1(1) q3_1(1) q3_1(2) q3_1(2) q3_2(1) q3_2(1) q3_2(2) q3_2(2); 0094 0 0 0 0 0 0 0 0; 0095 0 0 0 0 0 0 0 0; 0096 0 0 0 0 0 0 0 0]; 0097 0098 %leave only the real part of the solutions 0099 q=real(q); 0100 0101 %Note that in this robot, the joint q3 has a non-simmetrical range. In this 0102 %case, the joint ranges from 60 deg to -219 deg, thus, the typical normalizing 0103 %step is avoided in this angle (the next line is commented). When solving 0104 %for the orientation, the solutions are normalized to the [-pi, pi] range 0105 %only for the theta4, theta5 and theta6 joints. 0106 0107 %normalize q to [-pi, pi] 0108 q(1,:) = normalize(q(1,:)); 0109 q(2,:) = normalize(q(2,:)); 0110 0111 % solve for the last three joints 0112 % for any of the possible combinations (theta1, theta2, theta3) 0113 for i=1:2:size(q,2), 0114 % use solve_spherical_wrist2 for the particular orientation 0115 % of the systems in this ABB robot 0116 % use either the geometric or algebraic method. 0117 % the function solve_spherical_wrist2 is used due to the relative 0118 % orientation of the last three DH reference systems. 0119 0120 %use either one algebraic method or the geometric 0121 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1, 'geometric'); %wrist up 0122 qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1,'algebraic'); %wrist up 0123 qtemp(4:6)=normalize(qtemp(4:6)); 0124 q(:,i)=qtemp; 0125 0126 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'geometric'); %wrist down 0127 qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'algebraic'); %wrist down 0128 qtemp(4:6)=normalize(qtemp(4:6)); 0129 q(:,i+1)=qtemp; 0130 end 0131 0132 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0133 % solve for second joint theta2, two different 0134 % solutions are returned, corresponding 0135 % to elbow up and down solution 0136 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0137 function q2 = solve_for_theta2(robot, q, Pm) 0138 0139 %Evaluate the parameters 0140 d = eval(robot.DH.d); 0141 a = eval(robot.DH.a); 0142 0143 %See geometry 0144 L2=a(2); 0145 L3=sqrt(d(4)^2+a(3)^2); 0146 0147 %given q1 is known, compute first DH transformation 0148 T01=dh(robot, q, 1); 0149 0150 %Express Pm in the reference system 1, for convenience 0151 p1 = inv(T01)*[Pm; 1]; 0152 0153 r = sqrt(p1(1)^2 + p1(2)^2); 0154 0155 beta = atan2(-p1(2), p1(1)); 0156 gamma = (acos((L2^2+r^2-L3^2)/(2*r*L2))); 0157 0158 if ~isreal(gamma) 0159 disp('WARNING:inversekinematic_irb6650_90_390: the point is not reachable for this configuration, imaginary solutions'); 0160 %gamma = real(gamma); 0161 end 0162 0163 %return two possible solutions 0164 %elbow up and elbow down 0165 %the order here is important and is coordinated with the function 0166 %solve_for_theta3 0167 q2(1) = pi/2 - beta - gamma; %elbow up 0168 q2(2) = pi/2 - beta + gamma; %elbow down 0169 0170 0171 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0172 % solve for third joint theta3, two different 0173 % solutions are returned, corresponding 0174 % to elbow up and down solution 0175 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0176 function q3 = solve_for_theta3(robot, q, Pm) 0177 0178 %Evaluate the parameters 0179 d = eval(robot.DH.d); 0180 a = eval(robot.DH.a); 0181 0182 %See geometry 0183 L2=a(2); 0184 L3=sqrt(d(4)^2+a(3)^2); 0185 0186 %given q1 is known, compute first DH transformation 0187 T01=dh(robot, q, 1); 0188 0189 %Express Pm in the reference system 1, for convenience 0190 p1 = inv(T01)*[Pm; 1]; 0191 0192 r = sqrt(p1(1)^2 + p1(2)^2); 0193 0194 eta = (acos((L2^2 + L3^2 - r^2)/(2*L2*L3))); 0195 0196 if ~isreal(eta) 0197 disp('WARNING:inversekinematic_irb6650_90_390: the point is not reachable for this configuration, imaginary solutions'); 0198 %eta = real(eta); 0199 end 0200 0201 %return two possible solutions 0202 %elbow up and elbow down solutions 0203 %the order here is important 0204 q3(1) = -(atan(d(4)/a(3))+eta - pi); 0205 q3(2) = -(pi+atan(d(4)/a(3))-eta); 0206 0207 % %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0208 % % solve for second joint theta2, two different 0209 % % solutions are returned, corresponding 0210 % % to elbow up and down solution 0211 % %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0212 % function q2 = solve_for_theta2(robot, q, Pm) 0213 % 0214 % %Evaluate the parameters 0215 % theta = eval(robot.DH.theta); 0216 % d = eval(robot.DH.d); 0217 % a = eval(robot.DH.a); 0218 % alpha = eval(robot.DH.alpha); 0219 % 0220 % %See geometry 0221 % L2=a(2); 0222 % L3=d(4); 0223 % A2=a(3); 0224 % 0225 % %See geometry of the robot 0226 % %compute L4 0227 % L4 = sqrt(A2^2 + L3^2); 0228 % 0229 % %The inverse kinematic problem can be solved as in the IRB 140 (for example) 0230 % 0231 % %given q1 is known, compute first DH transformation 0232 % T01=dh(robot, q, 1); 0233 % 0234 % %Express Pm in the reference system 1, for convenience 0235 % p1 = inv(T01)*[Pm; 1]; 0236 % 0237 % r = sqrt(p1(1)^2 + p1(2)^2); 0238 % 0239 % beta = atan2(-p1(2), p1(1)); 0240 % gamma = real(acos((L2^2+r^2-L4^2)/(2*r*L2))); 0241 % 0242 % %return two possible solutions 0243 % %elbow up and elbow down 0244 % %the order here is important and is coordinated with the function 0245 % %solve_for_theta3 0246 % q2(1) = pi/2 - beta - gamma; %elbow up 0247 % q2(2) = pi/2 - beta + gamma; %elbow down 0248 % 0249 % 0250 % %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0251 % % solve for third joint theta3, two different 0252 % % solutions are returned, corresponding 0253 % % to elbow up and down solution 0254 % %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0255 % function q3 = solve_for_theta3(robot, q, Pm) 0256 % 0257 % %Evaluate the parameters 0258 % theta = eval(robot.DH.theta); 0259 % d = eval(robot.DH.d); 0260 % a = eval(robot.DH.a); 0261 % alpha = eval(robot.DH.alpha); 0262 % 0263 % %See geometry 0264 % L2=a(2); 0265 % L3=d(4); 0266 % A2=a(3); 0267 % 0268 % %See geometry of the robot 0269 % %compute L4 0270 % L4 = sqrt(A2^2 + L3^2); 0271 % 0272 % %the angle phi is fixed 0273 % phi=acos((A2^2+L4^2-L3^2)/(2*A2*L4)); 0274 % 0275 % %given q1 is known, compute first DH transformation 0276 % T01=dh(robot, q, 1); 0277 % 0278 % %Express Pm in the reference system 1, for convenience 0279 % p1 = inv(T01)*[Pm; 1]; 0280 % 0281 % r = sqrt(p1(1)^2 + p1(2)^2); 0282 % 0283 % eta = real(acos((L2^2 + L4^2 - r^2)/(2*L2*L4))); 0284 % 0285 % %return two possible solutions 0286 % %elbow up and elbow down solutions 0287 % %the order here is important 0288 % q3(1) = pi - phi- eta; 0289 % q3(2) = pi - phi + eta; 0290 %