Home > arte3.2.0 > robots > ABB > IRB120 > inversekinematic_irb120.m

inversekinematic_irb120

PURPOSE ^

%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

SYNOPSIS ^

function q = inversekinematic_irb120(robot, T)

DESCRIPTION ^

%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
   Q = INVERSEKINEMATIC_IRB120(robot, T)    
   Solves the inverse kinematic problem for the ABB IRB 120 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_IRB120 returns 8 possible solutions, thus,
   Q is a 6x8 matrix where each column stores 6 feasible joint values.

   
   Example code:

   abb=load_robot('abb', 'IRB120');
   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.
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%

CROSS-REFERENCE INFORMATION ^

This function calls: This function is called by:

SUBFUNCTIONS ^

SOURCE CODE ^

0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0002 %   Q = INVERSEKINEMATIC_IRB120(robot, T)
0003 %   Solves the inverse kinematic problem for the ABB IRB 120 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_IRB120 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', 'IRB120');
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_irb120(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 
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 
0100 %leave only the real part of the solutions
0101 q=real(q);
0102 
0103 %Note that in this robot, the joint q3 has a non-simmetrical range. In this
0104 %case, the joint ranges from 60� to -219�, thus, the typical normalizing
0105 %step is avoided in this angle (the next line is commented). When solving
0106 %for the orientation, the solutions are normalized to the [-pi, pi] range
0107 %only for the theta4, theta5 and theta6 joints.
0108 
0109 %normalize q to [-pi, pi]
0110 q(1,:) = normalize(q(1,:));
0111 q(2,:) = normalize(q(2,:));
0112 
0113 % solve for the last three joints
0114 % for any of the possible combinations (theta1, theta2, theta3)
0115 for i=1:2:size(q,2),
0116     qtemp = solve_spherical_wrist2(robot, q(:,i), T, 1,'algebraic'); %wrist up
0117     qtemp(4:6)=normalize(qtemp(4:6));
0118     q(:,i)=qtemp;
0119     
0120     qtemp = solve_spherical_wrist2(robot, q(:,i), T, -1, 'algebraic'); %wrist up
0121     qtemp(4:6)=normalize(qtemp(4:6));
0122     q(:,i+1)=qtemp;
0123 end
0124 
0125 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0126 % solve for second joint theta2, two different
0127 % solutions are returned, corresponding
0128 % to elbow up and down solution
0129 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0130 function q2 = solve_for_theta2(robot, q, Pm)
0131 
0132 %Evaluate the parameters
0133 %theta = eval(robot.DH.theta);
0134 d = eval(robot.DH.d);
0135 a = eval(robot.DH.a);
0136 %alpha = eval(robot.DH.alpha);
0137 
0138 %See geometry
0139 L2=a(2);
0140 L3=d(4);
0141 A2=a(3);
0142 
0143 %See geometry of the robot
0144 %compute L4
0145 L4 = sqrt(A2^2 + L3^2);
0146 
0147 %The inverse kinematic problem can be solved as in the IRB 140 (for example)
0148 
0149 %given q1 is known, compute first DH transformation
0150 T01=dh(robot, q, 1);
0151 
0152 %Express Pm in the reference system 1, for convenience
0153 p1 = inv(T01)*[Pm; 1];
0154 
0155 r = sqrt(p1(1)^2 + p1(2)^2);
0156 
0157 beta = atan2(-p1(2), p1(1));
0158 gamma = real(acos((L2^2+r^2-L4^2)/(2*r*L2)));
0159 
0160 %return two possible solutions
0161 %elbow up and elbow down
0162 %the order here is important and is coordinated with the function
0163 %solve_for_theta3
0164 q2(1) = pi/2 - beta - gamma; %elbow up
0165 q2(2) = pi/2 - beta + gamma; %elbow down
0166 
0167 
0168 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0169 % solve for third joint theta3, two different
0170 % solutions are returned, corresponding
0171 % to elbow up and down solution
0172 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0173 function q3 = solve_for_theta3(robot, q, Pm)
0174 
0175 %Evaluate the parameters
0176 %theta = eval(robot.DH.theta);
0177 d = eval(robot.DH.d);
0178 a = eval(robot.DH.a);
0179 %alpha = eval(robot.DH.alpha);
0180 
0181 %See geometry
0182 L2=a(2);
0183 L3=d(4);
0184 A2=a(3);
0185 
0186 %See geometry of the robot
0187 %compute L4
0188 L4 = sqrt(A2^2 + L3^2);
0189 
0190 %the angle phi is fixed
0191 phi=acos((A2^2+L4^2-L3^2)/(2*A2*L4));
0192 
0193 %given q1 is known, compute first DH transformation
0194 T01=dh(robot, q, 1);
0195 
0196 %Express Pm in the reference system 1, for convenience
0197 p1 = inv(T01)*[Pm; 1];
0198 
0199 r = sqrt(p1(1)^2 + p1(2)^2);
0200 
0201 eta = real(acos((L2^2 + L4^2 - r^2)/(2*L2*L4)));
0202 
0203 %return two possible solutions
0204 %elbow up and elbow down solutions
0205 %the order here is important
0206 q3(1) = pi - phi- eta; 
0207 q3(2) = pi - phi + eta; 
0208 
0209 
0210

Generated on Fri 03-Jan-2014 12:20:01 by m2html © 2005