%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% PARAMETERS Returns a data structure containing the parameters of the example 2 DOF planar robot. Author: Arturo Gil. Universidad Miguel Hern�ndez de Elche. email: arturo.gil@umh.es date: 03/03/2012 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
0001 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0002 % PARAMETERS Returns a data structure containing the parameters of the 0003 % example 2 DOF planar robot. 0004 % 0005 % Author: Arturo Gil. Universidad Miguel Hern�ndez de Elche. 0006 % email: arturo.gil@umh.es date: 03/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 1DOF planar arm'; 0028 0029 %kinematic data DH parameters 0030 robot.DH.theta='[q(1)]'; 0031 robot.DH.d='[0]'; 0032 robot.DH.a='[1]'; 0033 robot.DH.alpha='[0]'; 0034 0035 %number of degrees of freedom 0036 robot.DOF = 1; 0037 0038 %rotational: R, translational: T 0039 robot.kind=['R']; 0040 0041 %Jacobian matrix 0042 robot.J=[]; 0043 0044 0045 %Function name to compute inverse kinematic 0046 robot.inversekinematic_fn = 'inversekinematic_1dofplanar(robot, T)'; 0047 robot.directkinematic_fn = 'directkinematic(robot, q)'; 0048 0049 %minimum and maximum rotation angle in rad 0050 robot.maxangle =[deg2rad(-180) deg2rad(180)];%deg2rad(-180) deg2rad(180)]; %Axis 2, minimum, maximum 0051 0052 %maximum absolute speed of each joint rad/s or m/s 0053 robot.velmax = []; %empty, not available 0054 0055 robot.accelmax=robot.velmax/0.1; % 0.1 is here an acceleration time 0056 0057 % end effectors maximum velocity 0058 robot.linear_velmax = 0; %m/s, example, not available 0059 0060 0061 %base reference system 0062 robot.T0 = eye(4); 0063 0064 %INITIALIZATION OF VARIABLES REQUIRED FOR THE SIMULATION 0065 %position, velocity and acceleration 0066 robot=init_sim_variables(robot); 0067 robot.path = pwd; 0068 0069 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0070 %GRAPHICS 0071 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0072 %read graphics files 0073 robot.graphical.has_graphics=1; 0074 robot.graphical.color = [25 20 40]; 0075 %for transparency 0076 robot.graphical.draw_transparent=0; 0077 %draw DH systems 0078 robot.graphical.draw_axes=1; 0079 %DH system length and Font size, standard is 1/10. Select 2/20, 3/30 for 0080 %bigger robots 0081 robot.graphical.axes_scale=1; 0082 %adjust for a default view of the robot 0083 robot.axis=[-2.2 2.2 -2.2 2.2 0 2.2] 0084 robot = read_graphics(robot); 0085 0086 0087 %INITIALIZATION OF VARIABLES REQUIRED FOR THE SIMULATION 0088 %position, velocity and acceleration 0089 robot.q=[0 ]'; 0090 robot.qd=[0 ]'; 0091 robot.qdd=[0 ]'; 0092 robot.time = []; 0093 0094 robot.q_vector=[]; 0095 robot.qd_vector=[]; 0096 robot.qdd_vector=[]; 0097 0098 0099 robot.last_target=directkinematic(robot, robot.q); 0100 robot.last_zone_data = 'fine'; 0101 0102 0103 0104 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0105 % DYNAMIC PARAMETERS 0106 %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% 0107 robot.has_dynamics=1; 0108 0109 %consider friction or not 0110 robot.dynamics.friction=0; 0111 0112 %link masses (kg) 0113 robot.dynamics.masses=[1]; 0114 0115 %COM of each link with respect to own reference system 0116 robot.dynamics.r_com=[-0.5 0 0 ];%(rx, ry, rz) link 2 0117 0118 %link masses 0119 m1 = robot.dynamics.masses(1); 0120 %m2 = robot.dynamics.masses(2); 0121 0122 L1 = robot.DH.a(1); 0123 %L2 = robot.DH.a(2); 0124 0125 0126 %Inertia matrices of each link 0127 % Ixx Iyy Izz Ixy Iyz Ixz, or each row 0128 robot.dynamics.Inertia=[0 0 m1*L1/3 0 0 0]; 0129 0130 0131 %Inertia of the rotor 0132 robot.motors.Inertia=[0 ]; 0133 %Reduction ration motor/joint speed 0134 robot.motors.G=[1]; 0135 0136 0137 %Viscous friction factor of the motor 0138 robot.motors.Viscous = [0 ]; 0139 %Coulomb friction of the motor 0140 %Tc+, Tc- 0141 robot.motors.Coulomb = [0 0 ]; 0142 0143 %Obtained from motor catalog under practicals/inverse_dynamics 0144 % R(Ohm) L(H) Kv (V/rad/s):speed constant Kp (Nm/A):torque constant Max_current (A) 0145 robot.motors.constants=[0.345 0.273e-3 2.3474e-05 84.9e-3 139];%these correspond to Maxon, 167132; 0146 0147 0148 %robot.motors=load_motors([5 5 5 4 4 4]); 0149 %Speed reductor at each joint 0150 %robot.motors.G=[300 300 300 300 300 300]; 0151 0152 0153 0154