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