%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% PARAMETERS Returns a data structure containing the parameters of the example 3 DOF planar robot. Author: Arturo Gil. Universidad Miguel Hernández de Elche. email: arturo.gil@umh.es date: 05/03/2012 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0002 % PARAMETERS Returns a data structure containing the parameters of the 0003 % example 3 DOF planar robot. 0004 % 0005 % Author: Arturo Gil. Universidad Miguel Hernández de Elche. 0006 % email: arturo.gil@umh.es date: 05/03/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='Example 3DOF planar arm'; 0028 0029 %kinematic data DH parameters 0030 robot.DH.theta='[q(1) q(2) q(3)]'; 0031 robot.DH.d='[0 0 0]'; 0032 robot.DH.a='[1 1 1]'; 0033 robot.DH.alpha='[0 0 0]'; 0034 0035 %number of degrees of freedom 0036 robot.DOF = 3; 0037 0038 %Jacobian matrix 0039 robot.J=[]; 0040 0041 robot.kind=['R' 'R' 'R']; 0042 0043 0044 %Function name to compute inverse kinematic 0045 robot.inversekinematic_fn = 'inversekinematic_3dofplanar(robot, T)'; 0046 robot.directkinematic_fn = 'directkinematic(robot, q)'; 0047 0048 %minimum and maximum rotation angle in rad 0049 robot.maxangle =[deg2rad(-180) deg2rad(180); %Axis 1, minimum, maximum 0050 deg2rad(-180) deg2rad(180); 0051 deg2rad(-180) deg2rad(180)]; %Axis 2, minimum, maximum 0052 0053 %maximum absolute speed of each joint rad/s or m/s 0054 robot.velmax = []; %empty, not available 0055 0056 robot.accelmax=robot.velmax/0.1; % 0.1 is here an acceleration time 0057 % end effectors maximum velocity 0058 robot.linear_velmax = 0; %m/s, example, not available 0059 0060 %base reference system 0061 robot.T0 = eye(4); 0062 0063 %INITIALIZATION OF VARIABLES REQUIRED FOR THE SIMULATION 0064 %position, velocity and acceleration 0065 robot=init_sim_variables(robot); 0066 robot.path = pwd; 0067 0068 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0069 %GRAPHICS 0070 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0071 %read graphics files 0072 robot.graphical.has_graphics=1; 0073 robot.graphical.color = [255 20 40]./255; 0074 %for transparency 0075 robot.graphical.draw_transparent=0; 0076 %draw DH systems 0077 robot.graphical.draw_axes=1; 0078 %DH system length and Font size, standard is 1/10. Select 2/20, 3/30 for 0079 %bigger robots 0080 robot.graphical.axes_scale=1; 0081 %adjust for a default view of the robot 0082 robot.axis=[-3.5 3.5 -3.5 3.5 0 1] 0083 robot = read_graphics(robot); 0084 0085 0086 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0087 %DYNAMIC PARAMETERS 0088 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0089 robot.has_dynamics=1; 0090 0091 %consider friction in the computations 0092 robot.dynamics.friction=0; 0093 0094 %link masses (kg) 0095 robot.dynamics.masses=[1 1 1] ; 0096 0097 %COM of each link with respect to own reference system 0098 robot.dynamics.r_com=[-0.5 0 0; %(rx, ry, rz) link 1 0099 -0.5 0 0; 0100 -0.5 0 0];%(rx, ry, rz) link 2 0101 0102 %link masses 0103 m1 = robot.dynamics.masses(1); 0104 m2 = robot.dynamics.masses(2); 0105 m3 = robot.dynamics.masses(3); 0106 0107 L1 = robot.DH.a(1); 0108 L2 = robot.DH.a(2); 0109 L3 = robot.DH.a(3); 0110 0111 %Momentos de inercia de cada eslabon. 0112 % Ixx Iyy Izz Ixy Iyz Ixz, por cada fila 0113 robot.dynamics.Inertia=[0 0 m1*L1/3 0 0 0; 0114 0 0 m2*L2/3 0 0 0; 0115 0 0 m3*L3/3 0 0 0]; 0116 0117 %Actuator rotor inertia 0118 robot.motors.Inertia=[0 0 0]; 0119 %Reduction ratio motor/joint speed 0120 robot.motors.G=[1 1 1]; 0121 %consider friction 0122 robot.friction=1; 0123 %Viscous friction factor, motor referred 0124 %robot.B = [1e-3 1e-3 1e-3]; 0125 robot.motors.Viscous = [10 10 10]; 0126 %Coulomb friction, motor referred 0127 robot.motors.Coulomb = [0 0; 0128 0 0; 0129 0 0]; 0130