%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Q = INVERSEKINEMATIC_IRB52(robot, T) Solves the inverse kinematic problem for the ABB IRB 52 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_IRB52 returns 8 possible solutions, thus, Q is a 6x8 matrix where each column stores 6 feasible joint values. Example code: abb=load_robot('ABB', 'IRB52'); 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. %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0002 % Q = INVERSEKINEMATIC_IRB52(robot, T) 0003 % Solves the inverse kinematic problem for the ABB IRB 52 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_IRB52 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', 'IRB52'); 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 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 0045 % Nos hemos basado en la cinem�tica inversa del IRB140, pues ambos robots 0046 % son muy parecidos, y hemos le�do la resoluci�n de la cinem�tica inversa y 0047 % nos vale para nuestro robot. 0048 function [q] = inversekinematic_irb52(robot, T) 0049 0050 %initialize q, 0051 %eight possible solutions are generally feasible 0052 q=zeros(6,8); 0053 0054 %Evaluate the parameters 0055 theta = eval(robot.DH.theta); 0056 d = eval(robot.DH.d); 0057 a = eval(robot.DH.a); 0058 alpha = eval(robot.DH.alpha); 0059 0060 0061 %See geometry at the reference for this robot 0062 L1=d(1); 0063 L2=a(2); 0064 L3=d(4); 0065 L6=d(6); 0066 0067 A1 = a(1); 0068 0069 0070 %T= [ nx ox ax Px; 0071 % ny oy ay Py; 0072 % nz oz az Pz]; 0073 Px=T(1,4); 0074 Py=T(2,4); 0075 Pz=T(3,4); 0076 0077 %Compute the position of the wrist, being W the Z component of the end effector's system 0078 W = T(1:3,3); 0079 0080 % Pm: wrist position 0081 Pm = [Px Py Pz]' - L6*W; 0082 0083 %first joint, two possible solutions admited: 0084 % if q(1) is a solution, then q(1) + pi is also a solution 0085 q1=atan2(Pm(2), Pm(1)); 0086 0087 0088 %solve for q2 0089 q2_1=solve_for_theta2(robot, [q1 0 0 0 0 0 0], Pm); 0090 0091 q2_2=solve_for_theta2(robot, [q1+pi 0 0 0 0 0 0], Pm); 0092 0093 %solve for q3 0094 q3_1=solve_for_theta3(robot, [q1 0 0 0 0 0 0], Pm); 0095 0096 q3_2=solve_for_theta3(robot, [q1+pi 0 0 0 0 0 0], Pm); 0097 0098 0099 %Arrange solutions, there are 8 possible solutions so far. 0100 % if q1 is a solution, q1* = q1 + pi is also a solution. 0101 % For each (q1, q1*) there are two possible solutions 0102 % for q2 and q3 (namely, elbow up and elbow up solutions) 0103 % So far, we have 4 possible solutions. Howefer, for each triplet (theta1, theta2, theta3), 0104 % there exist two more possible solutions for the last three joints, generally 0105 % called wrist up and wrist down solutions. For this reason, 0106 %the next matrix doubles each column. For each two columns, two different 0107 %configurations for theta4, theta5 and theta6 will be computed. These 0108 %configurations are generally referred as wrist up and wrist down solution 0109 q = [q1 q1 q1 q1 q1+pi q1+pi q1+pi q1+pi; 0110 q2_1(1) q2_1(1) q2_1(2) q2_1(2) q2_2(1) q2_2(1) q2_2(2) q2_2(2); 0111 q3_1(1) q3_1(1) q3_1(2) q3_1(2) q3_2(1) q3_2(1) q3_2(2) q3_2(2); 0112 0 0 0 0 0 0 0 0; 0113 0 0 0 0 0 0 0 0; 0114 0 0 0 0 0 0 0 0]; 0115 0116 %leave only the real part of the solutions 0117 q=real(q); 0118 0119 %Note that in this robot, the joint q3 has a non-simmetrical range. In this 0120 %case, the joint ranges from 60 deg to -219 deg, thus, the typical normalizing 0121 %step is avoided in this angle (the next line is commented). When solving 0122 %for the orientation, the solutions are normalized to the [-pi, pi] range 0123 %only for the theta4, theta5 and theta6 joints. 0124 0125 %normalize q to [-pi, pi] 0126 q(1,:) = normalize(q(1,:)); 0127 q(2,:) = normalize(q(2,:)); 0128 0129 % solve for the last three joints 0130 % for any of the possible combinations (theta1, theta2, theta3) 0131 for i=1:2:size(q,2), 0132 % use solve_spherical_wrist2 for the particular orientation 0133 % of the systems in this ABB robot 0134 % use either the geometric or algebraic method. 0135 % the function solve_spherical_wrist2 is used due to the relative 0136 % orientation of the last three DH reference systems. 0137 0138 %use either one algebraic method or the geometric 0139 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1, 'geometric'); %wrist up 0140 qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1,'algebraic'); %wrist up 0141 qtemp(4:6)=normalize(qtemp(4:6)); 0142 q(:,i)=qtemp; 0143 0144 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'geometric'); %wrist down 0145 qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'algebraic'); %wrist down 0146 qtemp(4:6)=normalize(qtemp(4:6)); 0147 q(:,i+1)=qtemp; 0148 end 0149 0150 0151 0152 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0153 % solve for second joint theta2, two different 0154 % solutions are returned, corresponding 0155 % to elbow up and down solution 0156 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0157 function q2 = solve_for_theta2(robot, q, Pm) 0158 0159 %Evaluate the parameters 0160 d = eval(robot.DH.d); 0161 a = eval(robot.DH.a); 0162 0163 %See geometry 0164 L2=a(2); 0165 L3=d(4); 0166 0167 %given q1 is known, compute first DH transformation 0168 T01=dh(robot, q, 1); 0169 0170 %Express Pm in the reference system 1, for convenience 0171 p1 = inv(T01)*[Pm; 1]; 0172 0173 r = sqrt(p1(1)^2 + p1(2)^2); 0174 0175 beta = atan2(-p1(2), p1(1)); 0176 gamma = (acos((L2^2+r^2-L3^2)/(2*r*L2))); 0177 0178 if ~isreal(gamma) 0179 disp('WARNING:inversekinematic_irb52: the point is not reachable for this configuration, imaginary solutions'); 0180 %gamma = real(gamma); 0181 end 0182 0183 %return two possible solutions 0184 %elbow up and elbow down 0185 %the order here is important and is coordinated with the function 0186 %solve_for_theta3 0187 q2(1) = pi/2 - beta - gamma; %elbow up 0188 q2(2) = pi/2 - beta + gamma; %elbow down 0189 0190 0191 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0192 % solve for third joint theta3, two different 0193 % solutions are returned, corresponding 0194 % to elbow up and down solution 0195 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0196 function q3 = solve_for_theta3(robot, q, Pm) 0197 0198 %Evaluate the parameters 0199 d = eval(robot.DH.d); 0200 a = eval(robot.DH.a); 0201 0202 %See geometry 0203 L2=a(2); 0204 L3=d(4); 0205 0206 %given q1 is known, compute first DH transformation 0207 T01=dh(robot, q, 1); 0208 0209 %Express Pm in the reference system 1, for convenience 0210 p1 = inv(T01)*[Pm; 1]; 0211 0212 r = sqrt(p1(1)^2 + p1(2)^2); 0213 0214 eta = (acos((L2^2 + L3^2 - r^2)/(2*L2*L3))); 0215 0216 if ~isreal(eta) 0217 disp('WARNING:inversekinematic_irb52: the point is not reachable for this configuration, imaginary solutions'); 0218 %eta = real(eta); 0219 end 0220 0221 %return two possible solutions 0222 %elbow up and elbow down solutions 0223 %the order here is important 0224 q3(1) = pi/2 - eta; 0225 q3(2) = eta - 3*pi/2; 0226 0227 0228 0229 0230 0231 0232 %remove complex solutions for q for the q1+pi solutions 0233 function qreal = arrange_solutions(q) 0234 qreal=q(:,1:4); 0235 0236 %sum along rows if any angle is complex, for any possible solutions, then v(i) is complex 0237 v = sum(q, 1); 0238 0239 for i=5:8, 0240 if isreal(v(i)) 0241 qreal=[qreal q(:,i)]; %store the real solutions 0242 end 0243 end 0244 0245 qreal = real(qreal);