%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% Q = INVERSEKINEMATIC_IRB7600_500_230(robot, T) Solves the inverse kinematic problem for the ABB IRB7600_500_2300 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_IRB7600_500_2300 returns 8 possible solutions, thus, Q is a 6x8 matrix where each column stores 6 feasible joint values. Example code: >>abb=load_robot('ABB', 'IRB7600_500_2300'); >>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_IRB7600_500_230(robot, T) 0003 % Solves the inverse kinematic problem for the ABB IRB7600_500_2300 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_IRB7600_500_2300 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', 'IRB7600_500_2300'); 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 % 0021 % check that all of them are feasible solutions! 0022 % and every Ti equals T 0023 % 0024 % for i=1:8, 0025 % Ti = directkinematic(abb, qinv(:,i)) 0026 % end 0027 % 0028 % See also DIRECTKINEMATIC. 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_irb7600_500_230(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 a = eval(robot.DH.a); 0057 alpha = eval(robot.DH.alpha); 0058 0059 0060 %See geometry at the reference for this robot 0061 L1=d(1); 0062 L2=a(2); 0063 L3=d(4); 0064 A2=a(3); 0065 L6=d(6); 0066 0067 A1 = a(1); 0068 0069 %T= [ nx ox ax Px; 0070 % ny oy ay Py; 0071 % nz oz az Pz]; 0072 Px=T(1,4); 0073 Py=T(2,4); 0074 Pz=T(3,4); 0075 0076 %Compute the position of the wrist, being W the Z component of the end effector's system 0077 W = T(1:3,3); 0078 0079 % Pm: wrist position 0080 Pm = [Px Py Pz]' - L6*W; 0081 0082 %first joint, two possible solutions admited: 0083 % if q(1) is a solution, then q(1) + pi is also a solution 0084 q1=atan2(Pm(2), Pm(1)); 0085 0086 0087 %solve for q2 0088 q2_1=solve_for_theta2(robot, [q1 0 0 0 0 0 0], Pm); 0089 0090 q2_2=solve_for_theta2(robot, [q1+pi 0 0 0 0 0 0], Pm); 0091 0092 %solve for q3 0093 q3_1=solve_for_theta3(robot, [q1 0 0 0 0 0 0], Pm); 0094 0095 q3_2=solve_for_theta3(robot, [q1+pi 0 0 0 0 0 0], Pm); 0096 0097 0098 %Arrange solutions, there are 8 possible solutions so far. 0099 % if q1 is a solution, q1* = q1 + pi is also a solution. 0100 % For each (q1, q1*) there are two possible solutions 0101 % for q2 and q3 (namely, elbow up and elbow up solutions) 0102 % So far, we have 4 possible solutions. Howefer, for each triplet (theta1, theta2, theta3), 0103 % there exist two more possible solutions for the last three joints, generally 0104 % called wrist up and wrist down solutions. For this reason, 0105 %the next matrix doubles each column. For each two columns, two different 0106 %configurations for theta4, theta5 and theta6 will be computed. These 0107 %configurations are generally referred as wrist up and wrist down solution 0108 q = [q1 q1 q1 q1 q1+pi q1+pi q1+pi q1+pi; 0109 q2_1(1) q2_1(1) q2_1(2) q2_1(2) q2_2(1) q2_2(1) q2_2(2) q2_2(2); 0110 q3_1(1) q3_1(1) q3_1(2) q3_1(2) q3_2(1) q3_2(1) q3_2(2) q3_2(2); 0111 0 0 0 0 0 0 0 0; 0112 0 0 0 0 0 0 0 0; 0113 0 0 0 0 0 0 0 0]; 0114 0115 %leave only the real part of the solutions 0116 q=real(q); 0117 0118 %Note that in this robot, the joint q3 has a non-simmetrical range. In this 0119 %case, the joint ranges from 60 deg to -219 deg, thus, the typical normalizing 0120 %step is avoided in this angle (the next line is commented). When solving 0121 %for the orientation, the solutions are normalized to the [-pi, pi] range 0122 %only for the theta4, theta5 and theta6 joints. 0123 0124 %normalize q to [-pi, pi] 0125 q(1,:) = normalize(q(1,:)); 0126 q(2,:) = normalize(q(2,:)); 0127 0128 % solve for the last three joints 0129 % for any of the possible combinations (theta1, theta2, theta3) 0130 for i=1:2:size(q,2), 0131 % use solve_spherical_wrist2 for the particular orientation 0132 % of the systems in this ABB robot 0133 % use either the geometric or algebraic method. 0134 % the function solve_spherical_wrist2 is used due to the relative 0135 % orientation of the last three DH reference systems. 0136 0137 %use either one algebraic method or the geometric 0138 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1, 'geometric'); %wrist up 0139 qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1,'algebraic'); %wrist up 0140 qtemp(4:6)=normalize(qtemp(4:6)); 0141 q(:,i)=qtemp; 0142 0143 %qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'geometric'); %wrist down 0144 qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'algebraic'); %wrist down 0145 qtemp(4:6)=normalize(qtemp(4:6)); 0146 q(:,i+1)=qtemp; 0147 end 0148 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 A2=a(3); 0167 0168 %compute L4 0169 L4=sqrt(A2^2+L3^2); 0170 %given q1 is known, compute first DH transformation 0171 T01=dh(robot, q, 1); 0172 0173 %Express Pm in the reference system 1, for convenience 0174 p1 = inv(T01)*[Pm; 1]; 0175 0176 r = sqrt(p1(1)^2 + p1(2)^2); 0177 0178 beta = atan2(-p1(2), p1(1)); 0179 gamma = (acos((L2^2+r^2-L4^2)/(2*r*L2))); 0180 0181 if ~isreal(gamma) 0182 disp('WARNING:inversekinematic_irb7600_500_230: the point is not reachable for this configuration, imaginary solutions'); 0183 %gamma = real(gamma); 0184 end 0185 0186 %return two possible solutions 0187 %elbow up and elbow down 0188 %the order here is important and is coordinated with the function 0189 %solve_for_theta3 0190 q2(1) = pi/2 - beta - gamma; %elbow up 0191 q2(2) = pi/2 - beta + gamma; %elbow down 0192 0193 0194 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0195 % solve for third joint theta3, two different 0196 % solutions are returned, corresponding 0197 % to elbow up and down solution 0198 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0199 function q3 = solve_for_theta3(robot, q, Pm) 0200 0201 %Evaluate the parameters 0202 d = eval(robot.DH.d); 0203 a = eval(robot.DH.a); 0204 0205 %See geometry 0206 L2=a(2); 0207 L3=d(4); 0208 A2=a(3); 0209 0210 %See geometry of the robot 0211 L4=sqrt(A2^2+L3^2); 0212 %the angle phi is fixed 0213 phi= acos((A2^2-L3^2+L4^2)/(2*A2*L4)); 0214 0215 0216 %given q1 is known, compute first DH transformation 0217 T01=dh(robot, q, 1); 0218 0219 %Express Pm in the reference system 1, for convenience 0220 p1 = inv(T01)*[Pm; 1]; 0221 0222 r = sqrt(p1(1)^2 + p1(2)^2); 0223 0224 eta = (acos((L2^2 + L4^2 - r^2)/(2*L2*L4))); 0225 0226 if ~isreal(eta) 0227 disp('WARNING:inversekinematic_irb7600_500_230: the point is not reachable for this configuration, imaginary solutions'); 0228 %eta = real(eta); 0229 end 0230 0231 %return two possible solutions 0232 %elbow up and elbow down solutions 0233 %the order here is important 0234 q3(1) = pi - phi - eta; 0235 q3(2) = pi - phi + eta; 0236 0237 0238