1 %PUMA560AKB Load kinematic and dynamic data
for a Puma 560 manipulator
5 % Defines the
object 'p560m' in current workspace which describes the
6 % kinematic and dynamic characterstics of a Unimation Puma 560 manipulator
7 % modified DH conventions and
using the data and conventions of:
9 % Armstrong, Khatib and Burdick 1986.
10 %
"The Explicit Dynamic Model and Inertial Parameters of the Puma 560 Arm"
12 % Also define the vector qz which corresponds to the zero joint
13 % angle configuration, qr which is the vertical
'READY' configuration,
14 % and qstretch in which the arm is stretched out in the X direction.
16 % See also: ROBOT, PUMA560, STANFORD, TWOLINK.
18 % Copyright (C) 1993-2002, by Peter I. Corke
20 % 12/01 convert to object format
21 % $Log: puma560akb_motor.m,v $
22 % Revision 1.2 2004/07/06 02:16:36 gourdeau
25 % Revision 1.1 2004/05/12 13:34:37 elachance
28 % Revision 1.1 2003/02/06 04:31:36 gourdeau
31 % Revision 1.1 2002/12/17 02:32:22 elachance
34 % Revision 1.1 2002/12/13 04:50:14 elachance
37 % Revision 1.3 2002/04/01 11:47:15 pic
38 % General cleanup of code: help comments, see also, copyright, remnant dh/dyn
39 % references, clarification of functions.
44 % alpha A theta D sigma
45 L{1} = link([0 0 0 0 0],
'mod');
46 L{2} = link([-pi/2 0 0 0 0],
'mod');
47 L{3} = link([0 0.4318 0 -0.15005 0],
'mod');
48 L{4} = link([-pi/2 0.0203 0 -.4318 0],
'mod');
49 L{5} = link([pi/2 0 0 0 0],
'mod');
50 L{6} = link([-pi/2 0 0 0 0],
'mod');
52 %L{1} = link([0 0 0 0 0],
'mod');
53 %L{2} = link([-pi/2 0 0 0.2435 0],
'mod');
54 %L{3} = link([0 0.4318 0 -0.0934 0],
'mod');
55 %L{4} = link([pi/2 -0.0203 0 .4331 0],
'mod');
56 %L{5} = link([-pi/2 0 0 0 0],
'mod');
57 %L{6} = link([pi/2 0 0 0 0],
'mod');
68 L{2}.r = [0.068 0.006 -0.016];
69 L{3}.r = [0 -0.070 0.014 ];
70 L{4}.r = [0 0 -0.019];
74 % Ixx Iyy Izz Ixy Iyz Ixz
75 L{1}.I = [0 0 0.35 0 0 0];
76 L{2}.I = [.13 .524 .539 0 0 0];
77 L{3}.I = [.066 .0125 .066 0 0 0];
78 L{4}.I = [1.8e-3 1.8e-3 1.3e-3 0 0 0];
79 L{5}.I = [.3e-3 .3e-3 .4e-3 0 0 0];
80 L{6}.I = [.15e-3 .15e-3 .04e-3 0 0 0];
103 % viscous friction (motor referenced)
111 % Coulomb friction (motor referenced)
112 L{1}.Tc = [ 0.0 0.0];
113 L{2}.Tc = [ 0.0 0.0];
114 L{3}.Tc = [ 0.0 0.0];
115 L{4}.Tc = [ 0.0 0.0];
116 L{5}.Tc = [ 0.0 0.0];
117 L{6}.Tc = [ 0.0 0.0];
119 %L{1}.Tc = [ .395 -.435];
120 %L{2}.Tc = [ .126 -.071];
121 %L{3}.Tc = [ .132 -.105];
122 %L{4}.Tc = [ 11.2e-3 -16.9e-3];
123 %L{5}.Tc = [ 9.26e-3 -14.5e-3];
124 %L{6}.Tc = [ 3.96e-3 -10.5e-3];
129 qz = [0 0 0 0 0 0]; % zero angles, L shaped pose
130 qr = [0 -pi/2 pi/2 0 0 0]; % ready pose, arm up
131 qstretch = [0 0 pi/2 0 0 0]; % horizontal along x-axis
133 p560m = robot(L, 'Puma560-AKB', 'Unimation', 'AK&B');