%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% PARAMETERS Returns a data structure containing the parameters of the ABB IRB6620. Author: Arturo Gil. Universidad Miguel Hernández de Elche. email: arturo.gil@umh.es date: 09/01/2012 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0002 % PARAMETERS Returns a data structure containing the parameters of the 0003 % ABB IRB6620. 0004 % 0005 % Author: Arturo Gil. Universidad Miguel Hernández de Elche. 0006 % email: arturo.gil@umh.es date: 09/01/2012 0007 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0008 0009 % Copyright (C) 2012, by Arturo Gil Aparicio 0010 % 0011 % This file is part of ARTE (A Robotics Toolbox for Education). 0012 % 0013 % ARTE is free software: you can redistribute it and/or modify 0014 % it under the terms of the GNU Lesser General Public License as published by 0015 % the Free Software Foundation, either version 3 of the License, or 0016 % (at your option) any later version. 0017 % 0018 % ARTE is distributed in the hope that it will be useful, 0019 % but WITHOUT ANY WARRANTY; without even the implied warranty of 0020 % MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 0021 % GNU Lesser General Public License for more details. 0022 % 0023 % You should have received a copy of the GNU Leser General Public License 0024 % along with ARTE. If not, see <http://www.gnu.org/licenses/>. 0025 function robot = parameters() 0026 0027 robot.name= 'ABB_IRB6620LX'; 0028 0029 %Path where everything is stored for this robot 0030 robot.path = 'robots/abb/IRB6620'; 0031 0032 robot.DH.theta= '[0 q(2) q(3) q(4) q(5) q(6)+pi]'; 0033 robot.DH.d='[q(1) 0 0 0.887 0 0.2]'; 0034 robot.DH.a='[0.458 0.975 0.2 0 0 0]'; 0035 robot.DH.alpha= '[0 0 pi/2 pi/2 -pi/2 0]'; 0036 0037 robot.J=[]; 0038 0039 0040 robot.inversekinematic_fn = 'inversekinematic_irb6620lx(robot, T)'; 0041 0042 %number of degrees of freedom 0043 robot.DOF = 6; 0044 0045 %rotational: 0, translational: 1 0046 robot.kind=['T' 'R' 'R' 'R' 'R' 'R']; 0047 0048 %minimum and maximum rotation angle in rad 0049 robot.maxangle =[0 deg2rad(4); %Axis 1, minimum, maximum metros 0050 deg2rad(-125) deg2rad(125); %Axis 2, minimum, maximum 0051 deg2rad(-90) deg2rad(160); %Axis 3 0052 deg2rad(-300) deg2rad(300); %Axis 4: 0053 deg2rad(-130) deg2rad(130); %Axis 5 0054 deg2rad(-300) deg2rad(300)]; %Axis 6: 0055 0056 %maximum absolute speed of each joint rad/s or m/s 0057 robot.velmax = [deg2rad(100); %Axis 1, rad/s 0058 deg2rad(90); %Axis 2, rad/s 0059 deg2rad(90); %Axis 3, rad/s 0060 deg2rad(150); %Axis 4, rad/s 0061 deg2rad(120); %Axis 5, rad/s 0062 deg2rad(190)];%Axis 6, rad/s 0063 robot.accelmax=robot.velmax/0.1; % 0.1 is here an acceleration time 0064 % end effectors maximum velocity 0065 robot.linear_velmax = 1.0; %m/s, unavailable from datasheet 0066 0067 %base reference system 0068 %robot.T0 = inv([1 0 0 0;0 0 1 0; 0 -1 0 0;0 0 0 1]); 0069 robot.T0=eye(4); 0070 0071 %INITIALIZATION OF VARIABLES REQUIRED FOR THE SIMULATION 0072 %position, velocity and acceleration 0073 robot=init_sim_variables(robot); 0074 0075 0076 % GRAPHICS 0077 robot.graphical.has_graphics=1; 0078 robot.graphical.color = [240 50 10]./255; 0079 %for transparency 0080 robot.graphical.draw_transparent=0; 0081 %draw DH systems 0082 robot.graphical.draw_axes=1; 0083 %DH system length and Font size, standard is 1/10. Select 2/20, 3/30 for 0084 %bigger robots 0085 robot.graphical.axes_scale=1; 0086 %adjust for a default view of the robot 0087 robot.axis=[-6 6 -6 6 -4 4]; 0088 %read graphics files 0089 robot = read_graphics(robot); 0090 0091 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0092 %DYNAMIC PARAMETERS 0093 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0094 robot.has_dynamics=1; 0095 0096 %link masses (kg) 0097 robot.dynamics.masses=[326.982 89.619 80.846 49.318 7.283 1.686]; 0098 0099 %COM of each link with respect to own reference system 0100 robot.dynamics.r_com=[-316.874 1.377 -40.242; %(rx, ry, rz) link 1 0101 -552.473 -0.253 219.498; %(rx, ry, rz) link 2 0102 -120.048 18.679 2.201; %(rx, ry, rz) link 3 0103 1 442.422 -12.159;%(rx, ry, rz) link 4 0104 0 -89.606 -2.094;%(rx, ry, rz) link 5 0105 1 16.032 -3.930].*1e-3;%(rx, ry, rz) link 6 0106 0107 0108 %Inertia matrices of each link with respect to its D-H reference system. 0109 robot.dynamics.Inertia=[35.5307630619465,76.3147388769721,62.7770872661309,0.131721786807036,-0.637731134920212,-5.87048385153286; 0110 13.3386364580491,32.4037001118437,36.1957425196398,0.866790010319889,0.00543891938928600,10.8675859220909; 0111 1.92553868438793,3.35787383463243,3.78943248613387,-0.290429407043168,-0.204483156477234,-0.199291853261792; 0112 16.1102718353071,6.81439237229636,10.2418395340107,-0.0218202981960000,0.265212695895164,0.287981031562000; 0113 -0.0138921189843760,0.0373794232394120,-0.0218695382237880,-0.0585029529843760,-0.0564697985415640,-0.0585059539843760; 0114 0.00509586529186400,0.00462223710140000,0.00938631719046400,-6.42299520000000e-05,0.000112673711360000,4.40698000000000e-06] 0115 0116 robot.motors=load_motors([5 5 5 4 4 4]); 0117 %Speed reductor at each joint 0118 robot.motors.G=[300 300 300 300 300 300];