00001 %PUMA560AKB Load kinematic and dynamic data for a Puma 560 manipulator
00002 %
00003 % PUMA560AKB
00004 %
00005 % Defines the object 'p560m' in current workspace which describes the
00006 % kinematic and dynamic characterstics of a Unimation Puma 560 manipulator
00007 % modified DH conventions and using the data and conventions of:
00008 %
00009 % Armstrong, Khatib and Burdick 1986.
00010 % "The Explicit Dynamic Model and Inertial Parameters of the Puma 560 Arm"
00011 %
00012 % Also define the vector qz which corresponds to the zero joint
00013 % angle configuration, qr which is the vertical 'READY' configuration,
00014 % and qstretch in which the arm is stretched out in the X direction.
00015 %
00016 % See also: ROBOT, PUMA560, STANFORD, TWOLINK.
00017
00018 % Copyright (C) 1993-2002, by Peter I. Corke
00019 % CHANGES:
00020 % 12/01 convert to object format
00021 % $Log: puma560akb_motor.m,v $
00022 % Revision 1.2 2004/07/06 02:16:36 gourdeau
00023 % doxy etc
00024 %
00025 % Revision 1.1 2004/05/12 13:34:37 elachance
00026 % Initial revision
00027 %
00028 % Revision 1.1 2003/02/06 04:31:36 gourdeau
00029 % 1er rev Etienne L.
00030 %
00031 % Revision 1.1 2002/12/17 02:32:22 elachance
00032 % Initial revision
00033 %
00034 % Revision 1.1 2002/12/13 04:50:14 elachance
00035 % Initial revision
00036 %
00037 % Revision 1.3 2002/04/01 11:47:15 pic
00038 % General cleanup of code: help comments, see also, copyright, remnant dh/dyn
00039 % references, clarification of functions.
00040 %
00041 % $Revision: 1.2 $
00042
00043 clear L
00044 % alpha A theta D sigma
00045 L{1} = link([0 0 0 0 0], 'mod');
00046 L{2} = link([-pi/2 0 0 0 0], 'mod');
00047 L{3} = link([0 0.4318 0 -0.15005 0], 'mod');
00048 L{4} = link([-pi/2 0.0203 0 -.4318 0], 'mod');
00049 L{5} = link([pi/2 0 0 0 0], 'mod');
00050 L{6} = link([-pi/2 0 0 0 0], 'mod');
00051
00052 %L{1} = link([0 0 0 0 0], 'mod');
00053 %L{2} = link([-pi/2 0 0 0.2435 0], 'mod');
00054 %L{3} = link([0 0.4318 0 -0.0934 0], 'mod');
00055 %L{4} = link([pi/2 -0.0203 0 .4331 0], 'mod');
00056 %L{5} = link([-pi/2 0 0 0 0], 'mod');
00057 %L{6} = link([pi/2 0 0 0 0], 'mod');
00058
00059 L{1}.m = 0;
00060 L{2}.m = 17.4;
00061 L{3}.m = 4.8;
00062 L{4}.m = 0.82;
00063 L{5}.m = 0.34;
00064 L{6}.m = .09;
00065
00066 % rx ry rz
00067 L{1}.r = ;
00068 L{2}.r = ;
00069 L{3}.r = ;
00070 L{4}.r = ;
00071 L{5}.r = ;
00072 L{6}.r = ;
00073
00074 % Ixx Iyy Izz Ixy Iyz Ixz
00075 L{1}.I = ;
00076 L{2}.I = ;
00077 L{3}.I = ;
00078 L{4}.I = ;
00079 L{5}.I = ;
00080 L{6}.I = ;
00081
00082 L{1}.Jm = 200e-6;
00083 L{2}.Jm = 200e-6;
00084 L{3}.Jm = 200e-6;
00085 L{4}.Jm = 33e-6;
00086 L{5}.Jm = 33e-6;
00087 L{6}.Jm = 33e-6;
00088
00089 %L{1}.G = 1.0;
00090 %L{2}.G = 1.0;
00091 %L{3}.G = 1.0;
00092 %L{4}.G = 1.0;
00093 %L{5}.G = 1.0;
00094 %L{6}.G = 1.0;
00095
00096 L{1}.G = -62.6111;
00097 L{2}.G = 107.815;
00098 L{3}.G = -53.7063;
00099 L{4}.G = 76.0364;
00100 L{5}.G = 71.923;
00101 L{6}.G = 76.686;
00102
00103 % viscous friction (motor referenced)
00104 L{1}.B = 1.48e-3;
00105 L{2}.B = .817e-3;
00106 L{3}.B = 1.38e-3;
00107 L{4}.B = 71.2e-6;
00108 L{5}.B = 82.6e-6;
00109 L{6}.B = 36.7e-6;
00110
00111 % Coulomb friction (motor referenced)
00112 L{1}.Tc = ;
00113 L{2}.Tc = ;
00114 L{3}.Tc = ;
00115 L{4}.Tc = ;
00116 L{5}.Tc = ;
00117 L{6}.Tc = ;
00118
00119 %L{1}.Tc = ;
00120 %L{2}.Tc = ;
00121 %L{3}.Tc = ;
00122 %L{4}.Tc = ;
00123 %L{5}.Tc = ;
00124 %L{6}.Tc = ;
00125
00126 %
00127 % some useful poses
00128 %
00129 qz = ; % zero angles, L shaped pose
00130 qr = ; % ready pose, arm up
00131 qstretch = ; % horizontal along x-axis
00132
00133 p560m = robot(L, 'Puma560-AKB', 'Unimation', 'AK&B');
00134 clear L
00135
00136