1 %PUMA560 Load kinematic and dynamic data
for a Puma 560 manipulator
5 % Defines the
object 'p560' in the current workspace which describes the
6 % kinematic and dynamic % characterstics of a Unimation Puma 560 manipulator
7 %
using standard DH conventions.
8 % The model includes armature inertia and gear ratios.
10 % Also define the vector qz which corresponds to the zero joint
11 % angle configuration, qr which is the vertical
'READY' configuration,
12 % and qstretch in which the arm is stretched out in the X direction.
14 % See also: ROBOT, PUMA560AKB, STANFORD, TWOLINK.
18 % - the value of m1 is given as 0 here. Armstrong found no value for it
19 % and it does not appear in the equation for tau1 after the substituion
20 % is made to inertia about link frame rather than COG frame.
22 % 2/8/95 changed D3 to 150.05mm which is closer to data from Lee, AKB86 and Tarn
23 % fixed errors in COG for links 2 and 3
24 % 29/1/91 to agree with data from Armstrong etal. Due to their use
25 % of modified D&H params, some of the offsets Ai, Di are
26 % offset, and for links 3-5 swap Y and Z axes.
27 % 14/2/91 to use Paul's value of link twist (alpha) to be consistant
28 % with ARCL. This is the -ve of Lee's values, which means the
29 % zero angle position is a righty for Paul, and lefty for Lee.
30 % Note that gravity load torque is the motor torque necessary
31 % to keep the joint static, and is thus -ve of the gravity
34 % 8/95 fix bugs in COG data for Puma 560. This led to signficant errors in
36 % $Log: puma560_motor.m,v $
37 % Revision 1.2 2004/07/06 02:16:36 gourdeau
40 % Revision 1.1 2004/05/12 13:34:37 elachance
43 % Revision 1.1 2003/02/06 04:31:36 gourdeau
46 % Revision 1.1 2002/12/17 02:31:55 elachance
49 % Revision 1.3 2002/04/01 11:47:16 pic
50 % General cleanup of code: help comments, see also, copyright, remnant dh/dyn
51 % references, clarification of functions.
55 % Copyright (C) 1993-2002, by Peter I. Corke
59 L{1} = link([pi/2 0 0 0 0],
'standard');
60 L{2} = link([ 0 .4318 0 0 0],
'standard');
61 L{3} = link([-pi/2 .0203 0 .15005 0],
'standard');
62 L{4} = link([pi/2 0 0 .4318 0],
'standard');
63 L{5} = link([-pi/2 0 0 0 0],
'standard');
64 L{6} = link([0 0 0 0 0],
'standard');
66 %L{1} = link([pi/2 0 0 0 0],
'standard');
67 %L{2} = link([ 0 .4318 0 0 0],
'standard');
68 %L{3} = link([-pi/2 .0203 0 .15005 0],
'standard');
69 %L{4} = link([pi/2 0 0 .4318 0],
'standard');
70 %L{5} = link([-pi/2 0 0 0 0],
'standard');
71 %L{6} = link([0 0 0 0 0],
'standard');
82 L{2}.r = [ -.3638 .006 .2275];
83 L{3}.r = [ -.0203 -.0141 .070];
88 L{1}.I = [ 0 0.35 0 0 0 0];
89 L{2}.I = [ .13 .524 .539 0 0 0];
90 L{3}.I = [ .066 .086 .0125 0 0 0];
91 L{4}.I = [ 1.8e-3 1.3e-3 1.8e-3 0 0 0];
92 L{5}.I = [ .3e-3 .4e-3 .3e-3 0 0 0];
93 L{6}.I = [ .15e-3 .15e-3 .04e-3 0 0 0];
116 % viscous friction (motor referenced)
124 % Coulomb friction (motor referenced)
125 L{1}.Tc = [ 0.0 0.0];
126 L{2}.Tc = [ 0.0 0.0];
127 L{3}.Tc = [ 0.0 0.0];
128 L{4}.Tc = [ 0.0 0.0];
129 L{5}.Tc = [ 0.0 0.0];
130 L{6}.Tc = [ 0.0 0.0];
132 %L{1}.Tc = [ .395 -.435];
133 %L{2}.Tc = [ .126 -.071];
134 %L{3}.Tc = [ .132 -.105];
135 %L{4}.Tc = [ 11.2e-3 -16.9e-3];
136 %L{5}.Tc = [ 9.26e-3 -14.5e-3];
137 %L{6}.Tc = [ 3.96e-3 -10.5e-3];
143 qz = [0 0 0 0 0 0]; % zero angles, L shaped pose
144 qr = [0 pi/2 -pi/2 0 0 0]; % ready pose, arm up
145 qstretch = [0 0 -pi/2 0 0 0];
147 p560 = robot(L,
'Puma 560',
'Unimation',
'params of 8/95');
149 p560.name =
'Puma 560';
150 p560.manuf =
'Unimation';