%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Q = INVERSEKINEMATIC_IRB6620(robot, T) Solves the inverse kinematic problem for the ABB IRB 6620 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_IRB6620 returns 8 possible solutions, thus, Q is a 6x8 matrix where each column stores 6 feasible joint values. Example code: abb=load_robot('ABB', 'IRB6620'); 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_IRB6620(robot, T) 0003 % Solves the inverse kinematic problem for the ABB IRB 6620 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_IRB6620 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', 'IRB6620'); 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 % 0026 % See also DIRECTKINEMATIC. 0027 % 0028 % Author: Arturo Gil Aparicio 0029 % Universitas Miguel Hernandez, SPAIN. 0030 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0031 0032 % Copyright (C) 2012, by Arturo Gil Aparicio 0033 % 0034 % This file is part of ARTE (A Robotics Toolbox for Education). 0035 % 0036 % ARTE is free software: you can redistribute it and/or modify 0037 % it under the terms of the GNU Lesser General Public License as published by 0038 % the Free Software Foundation, either version 3 of the License, or 0039 % (at your option) any later version. 0040 % 0041 % ARTE is distributed in the hope that it will be useful, 0042 % but WITHOUT ANY WARRANTY; without even the implied warranty of 0043 % MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 0044 % GNU Lesser General Public License for more details. 0045 % 0046 % You should have received a copy of the GNU Leser General Public License 0047 % along with ARTE. If not, see <http://www.gnu.org/licenses/>. 0048 function q = inversekinematic_irb6620(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 L6=d(6); 0058 0059 0060 %T= [ nx ox ax Px; 0061 % ny oy ay Py; 0062 % nz oz az Pz]; 0063 Px=T(1,4); 0064 Py=T(2,4); 0065 Pz=T(3,4); 0066 0067 %Compute the position of the wrist, being W the Z component of the end effector's system 0068 W = T(1:3,3); 0069 0070 % Pm: wrist position 0071 Pm = [Px Py Pz]' - L6*W; 0072 0073 %first joint, two possible solutions admited: 0074 % if q(1) is a solution, then q(1) + pi is also a solution 0075 q1=atan2(Pm(2), Pm(1)); 0076 0077 0078 %solve for q2 0079 q2_1=solve_for_theta2(robot, [q1 0 0 0 0 0 0], Pm); 0080 %the other possible solution is q1 + pi 0081 q2_2=solve_for_theta2(robot, [q1+pi 0 0 0 0 0 0], Pm); 0082 0083 %solve for q3 0084 q3_1=solve_for_theta3(robot, [q1 0 0 0 0 0 0], Pm); 0085 %solver for q3 for both cases 0086 q3_2=solve_for_theta3(robot, [q1+pi 0 0 0 0 0 0], Pm); 0087 0088 0089 %the next matrix doubles each column. For each two columns, two different 0090 %configurations for theta4, theta5 and theta6 will be computed. These 0091 %configurations are generally referred as wrist up and wrist down solution 0092 q = [q1 q1 q1 q1 q1+pi q1+pi q1+pi q1+pi; 0093 q2_1(1) q2_1(1) q2_1(2) q2_1(2) q2_2(1) q2_2(1) q2_2(2) q2_2(2); 0094 q3_1(1) q3_1(1) q3_1(2) q3_1(2) q3_2(1) q3_2(1) q3_2(2) q3_2(2); 0095 0 0 0 0 0 0 0 0; 0096 0 0 0 0 0 0 0 0; 0097 0 0 0 0 0 0 0 0]; 0098 0099 %leave only the real part of the solutions 0100 q=real(q); 0101 0102 %Note that in this robot, the joint q3 has a non-simmetrical range. In this 0103 %case, the joint ranges from 60 deg to -219 deg, thus, the typical normalizing 0104 %step is avoided in this angle (the next line is commented). When solving 0105 %for the orientation, the solutions are normalized to the [-pi, pi] range 0106 %only for the theta4, theta5 and theta6 joints. 0107 0108 %normalize q to [-pi, pi] 0109 q(1,:) = normalize(q(1,:)); 0110 q(2,:) = normalize(q(2,:)); 0111 0112 % solve for the last three joints 0113 % for any of the possible combinations (theta1, theta2, theta3) 0114 for i=1:2:size(q,2), 0115 % use solve_spherical_wrist2 for the particular orientation 0116 % of the systems in this ABB robot 0117 % use either the geometric or algebraic method. 0118 % the function solve_spherical_wrist2 is used due to the relative 0119 % orientation of the last three DH reference systems. 0120 0121 %use either one algebraic method or the geometric 0122 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1, 'geometric'); %wrist up 0123 qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1,'algebraic'); %wrist up 0124 qtemp(4:6)=normalize(qtemp(4:6)); 0125 q(:,i)=qtemp; 0126 0127 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'geometric'); %wrist down 0128 qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'algebraic'); %wrist down 0129 qtemp(4:6)=normalize(qtemp(4:6)); 0130 q(:,i+1)=qtemp; 0131 end 0132 0133 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0134 % solve for second joint theta2, two different 0135 % solutions are returned, corresponding 0136 % to elbow up and down solution 0137 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0138 function q2 = solve_for_theta2(robot, q, Pm) 0139 0140 %Evaluate the parameters 0141 theta = eval(robot.DH.theta); 0142 d = eval(robot.DH.d); 0143 a = eval(robot.DH.a); 0144 alpha = eval(robot.DH.alpha); 0145 0146 %See geometry 0147 L2=a(2); 0148 L3=d(4); 0149 A2=a(3); 0150 0151 %See geometry of the robot 0152 %compute L4 0153 L4 = sqrt(A2^2 + L3^2); 0154 0155 %The inverse kinematic problem can be solved as in the IRB 140 (for example) 0156 0157 %given q1 is known, compute first DH transformation 0158 T01=dh(robot, q, 1); 0159 0160 %Express Pm in the reference system 1, for convenience 0161 p1 = inv(T01)*[Pm; 1]; 0162 0163 r = sqrt(p1(1)^2 + p1(2)^2); 0164 0165 beta = atan2(-p1(2), p1(1)); 0166 gamma = (acos((L2^2+r^2-L4^2)/(2*r*L2))); 0167 0168 if ~isreal(gamma) 0169 disp('WARNING:inversekinematic_irb6620: the point is not reachable for this configuration, imaginary solutions'); 0170 0171 end 0172 %return two possible solutions 0173 %elbow up and elbow down 0174 %the order here is important and is coordinated with the function 0175 %solve_for_theta3 0176 q2(1) = pi/2 - beta - gamma; %elbow up 0177 q2(2) = pi/2 - beta + gamma; %elbow down 0178 0179 0180 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0181 % solve for third joint theta3, two different 0182 % solutions are returned, corresponding 0183 % to elbow up and down solution 0184 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0185 function q3 = solve_for_theta3(robot, q, Pm) 0186 0187 %Evaluate the parameters 0188 theta = eval(robot.DH.theta); 0189 d = eval(robot.DH.d); 0190 a = eval(robot.DH.a); 0191 alpha = eval(robot.DH.alpha); 0192 0193 %See geometry 0194 L2=a(2); 0195 L3=d(4); 0196 A2=a(3); 0197 0198 %See geometry of the robot 0199 %compute L4 0200 L4 = sqrt(A2^2 + L3^2); 0201 0202 %the angle phi is fixed 0203 phi=acos((A2^2+L4^2-L3^2)/(2*A2*L4)); 0204 0205 %given q1 is known, compute first DH transformation 0206 T01=dh(robot, q, 1); 0207 0208 %Express Pm in the reference system 1, for convenience 0209 p1 = inv(T01)*[Pm; 1]; 0210 0211 r = sqrt(p1(1)^2 + p1(2)^2); 0212 0213 eta = (acos((L2^2 + L4^2 - r^2)/(2*L2*L4))); 0214 0215 if ~isreal(eta) 0216 disp('WARNING:inversekinematic_irb6620: the point is not reachable for this configuration, imaginary solutions'); 0217 0218 end 0219 0220 0221 %return two possible solutions 0222 %elbow up and elbow down solutions 0223 %the order here is important 0224 q3(1) = pi - phi- eta; 0225 q3(2) = pi - phi + eta; 0226 0227 0228