%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% PARAMETERS Returns a data structure containing the parameters of the ABB IRB1600. Author: . FALO Universidad Miguel Hernández de Elche. email: FALO@umh.es date: 09/01/2012 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0002 % PARAMETERS Returns a data structure containing the parameters of the 0003 % ABB IRB1600. 0004 % 0005 % Author: . FALO Universidad Miguel Hernández de Elche. 0006 % email: FALO@umh.es date: 09/01/2012 0007 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0008 0009 % Copyright (C) 2012, by FALO 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_irb1600_X145_m2004'; 0028 0029 %Path where everything is stored for this robot 0030 %robot.path = 'robots/abb/irb1600_X145_m2004'; 0031 0032 robot.DH.theta= '[q(1) q(2)-pi/2 q(3) q(4) q(5) q(6)+pi]'; 0033 robot.DH.d='[0.4865 0 0 0.6 0 0.065]'; 0034 robot.DH.a='[0.15 0.7 0 0 0 0]'; 0035 robot.DH.alpha= '[-pi/2 0 -pi/2 pi/2 -pi/2 0]'; 0036 robot.J=[]; 0037 0038 0039 robot.inversekinematic_fn = 'inversekinematic_abb_irb1600_X145_m2004(robot, T)'; 0040 0041 %number of degrees of freedom 0042 robot.DOF = 6; 0043 0044 %rotational: 0, translational: 1 0045 robot.kind=['R' 'R' 'R' 'R' 'R' 'R']; 0046 0047 %minimum and maximum rotation angle in rad 0048 robot.maxangle =[deg2rad(-180) deg2rad(180); %Axis 1, minimum, maximum 0049 deg2rad(-90) deg2rad(150); %Axis 2 0050 deg2rad(-245) deg2rad(65); %Axis 3: Unlimited (400º default) 0051 deg2rad(-200) deg2rad(200); %Axis 4 0052 deg2rad(-115) deg2rad(115); %Axis 5: Unlimited (800º default) 0053 deg2rad(-400) deg2rad(400)]; %Axis 6: Unlimited (800º default) 0054 0055 %maximum absolute speed of each joint rad/s or m/s 0056 robot.velmax = [deg2rad(150); %Axis 1, rad/s 0057 deg2rad(160); %Axis 2, rad/s 0058 deg2rad(170); %Axis 3, rad/s 0059 deg2rad(320); %Axis 4, rad/s 0060 deg2rad(400); %Axis 5, rad/s 0061 deg2rad(460)];%Axis 6, rad/s 0062 0063 robot.accelmax=robot.velmax/0.1; % 0.1 is here an acceleration time 0064 0065 % end effectors maximum velocity 0066 robot.linear_velmax = 2.5; %m/s 0067 0068 %base reference system 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 % GRAPHICS 0076 robot.graphical.has_graphics=1; 0077 robot.graphical.color = [255 20 51]./255; 0078 %for transparency 0079 robot.graphical.draw_transparent=0; 0080 %draw DH systems 0081 robot.graphical.draw_axes=1; 0082 %DH system length and Font size, standard is 1/10. Select 2/20, 3/30 for 0083 %bigger robots 0084 robot.graphical.axes_scale=1; 0085 %adjust for a default view of the robot 0086 robot.axis=[-1.75 1.75 -1.75 1.75 0 2]; 0087 %read graphics files 0088 robot = read_graphics(robot); 0089 0090 0091 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0092 %DYNAMIC PARAMETERS 0093 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0094 robot.has_dynamics=1; 0095 0096 %consider friction in the computations 0097 robot.dynamics.friction=0; 0098 0099 %link masses (kg) 0100 robot.dynamics.masses=[0 157.5 70 20 2.25 0.25]; %Total 250kg 0101 0102 %COM of each link with respect to own reference system 0103 robot.dynamics.r_com=[0 0.1 0; %(rx, ry, rz) link 1 0104 -0.4 0 0; %(rx, ry, rz) link 2 0105 0 0 0.3; %(rx, ry, rz) link 3 0106 0 0 0;%(rx, ry, rz) link 4 0107 0 0 -0.075;%(rx, ry, rz) link 5 0108 0 0 -0.0032];%(rx, ry, rz) link 6 0109 0110 %Inertia matrices of each link with respect to its D-H reference system. 0111 % Ixx Iyy Izz Ixy Iyz Ixz, for each row 0112 robot.dynamics.Inertia=[0 0.35 0 0 0 0; 0113 1.3 5.24 5.39 0 0 0; 0114 1 1.2 0.3 0 0 0; 0115 0.12 0.1 0.12 0 0 0; 0116 .3e-2 .4e-2 .3e-2 0 0 0; 0117 .15e-2 .15e-2 .04e-2 0 0 0]; 0118 robot.motors=load_motors([5 5 5 4 4 4]); 0119 %Speed reductor at each joint 0120 robot.motors.G=[300 300 300 300 300 300];