demo.cpp
Go to the documentation of this file.
1 /*
2 ROBOOP -- A robotics object oriented package in C++
3 Copyright (C) 1996-2004 Richard Gourdeau
4 
5 This library is free software; you can redistribute it and/or modify
6 it under the terms of the GNU Lesser General Public License as
7 published by the Free Software Foundation; either version 2.1 of the
8 License, or (at your option) any later version.
9 
10 This library is distributed in the hope that it will be useful,
11 but WITHOUT ANY WARRANTY; without even the implied warranty of
12 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 GNU Lesser General Public License for more details.
14 
15 You should have received a copy of the GNU Lesser General Public
16 License along with this library; if not, write to the Free Software
17 Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
18 
19 
20 Report problems and direct all questions to:
21 
22 Richard Gourdeau
23 Professeur Agrege
24 Departement de genie electrique
25 Ecole Polytechnique de Montreal
26 C.P. 6079, Succ. Centre-Ville
27 Montreal, Quebec, H3C 3A7
28 
29 email: richard.gourdeau@polymtl.ca
30 
31 -------------------------------------------------------------------------------
32 Revision_history:
33 
34 2003/02/03: Etienne Lachance
35  -Added quaternions example in homogen_demo.
36  -Using function set_plot2d for gnuplot graphs.
37  -Declare vector with "dof" instead of hardcoded value.
38  -Changed RobotMotor to Robot.
39 
40 2003/29/04: Etienne Lachance
41  -Using Robot("conf/puma560_dh.conf", "PUMA560_DH") in kinematics functions.
42 
43 2004/07/01: Ethan Tira-Thompson
44  -Added support for newmat's use_namespace #define, using ROBOOP namespace
45 
46 2004/08/13: Etienne Lachance
47  -Modified robot initialisation matrix.
48 
49 2005/11/15 : Richard Gourdeau
50  - Fixed error on PUMA560 without motor dynamics
51 -------------------------------------------------------------------------------
52 
53 */
54 
62 static const char rcsid[] = "$Id: demo.cpp,v 1.34 2006/05/16 16:27:43 gourdeau Exp $";
64 
65 #include "gnugraph.h"
66 #include "quaternion.h"
67 #include "robot.h"
68 #include "utils.h"
69 
70 #ifdef use_namespace
71 using namespace ROBOOP;
72 #endif
73 
74 void homogen_demo(void);
75 void kinematics_demo(void);
76 void dynamics_demo(void);
77 
78 
79 int main(void)
80 {
81  cout << "=====================================================\n";
82  cout << " ROBOOP -- A robotics object oriented package in C++ \n";;
83  cout << " DEMO program \n";
84  cout << "=====================================================\n";
85  cout << "\n";
86 
87  homogen_demo();
89  dynamics_demo();
90 
91  return(0);
92 }
93 
94 
95 void homogen_demo(void)
96 {
97  ColumnVector p1(3), p2(3), p3(3);
98  Real ott[] = {1.0,2.0,3.0};
99  Real tto[] = {3.0,2.0,1.0};
100 
101  cout << "\n";
102  cout << "=====================================================\n";
103  cout << "Homogeneous transformations\n";
104  cout << "=====================================================\n";
105  cout << "\n";
106  cout << "Translation of [1;2;3]\n";
107  p1 << ott;
108  cout << setw(7) << setprecision(3) << trans(p1);
109  cout << "\n";
110  cout << "\n";
111  cout << "Rotation of pi/6 around axis X\n";
112  cout << setw(7) << setprecision(3) << rotx(M_PI/6);
113  cout << "\n";
114 
115  cout << "\n";
116  cout << "Rotation of pi/8 around axis Y\n";
117  cout << setw(7) << setprecision(3) << roty(M_PI/8);
118  cout << "\n";
119 
120  cout << "\n";
121  cout << "Rotation of pi/3 around axis Z\n";
122  cout << setw(7) << setprecision(3) << rotz(M_PI/3);
123  cout << "\n";
124 
125  cout << "\n";
126  cout << "Rotation of pi/3 around axis [1;2;3]\n";
127  cout << setw(7) << setprecision(3) << rotk(M_PI/3,p1);
128  cout << "\n";
129 
130  cout << "\n";
131  cout << "Rotation of pi/6 around line [1;2;3] -- [3;2;1]\n";
132  p2 << tto;
133  cout << setw(7) << setprecision(3) << rotd(M_PI/3,p1,p2);
134  cout << "\n";
135 
136  cout << "\n";
137  cout << "Roll Pitch Yaw Rotation [1;2;3]\n";
138  cout << setw(7) << setprecision(3) << rpy(p1);
139  cout << "\n";
140 
141  cout << "\n";
142  cout << "Euler ZXZ Rotation [3;2;1]\n";
143  cout << setw(7) << setprecision(3) << eulzxz(p2);
144  cout << "\n";
145 
146  cout << "\n";
147  cout << "Inverse of Rotation around axis\n";
148  cout << setw(7) << setprecision(3) << irotk(rotk(M_PI/3,p1));
149  cout << "\n";
150 
151  cout << "\n";
152  cout << "Inverse of Roll Pitch Yaw Rotation\n";
153  cout << setw(7) << setprecision(3) << irpy(rpy(p1));
154  cout << "\n";
155 
156  cout << "\n";
157  cout << "Inverse of Euler ZXZ Rotation\n";
158  cout << setw(7) << setprecision(3) << ieulzxz(eulzxz(p2));
159  cout << "\n";
160 
161  cout << "\n";
162  cout << "Cross product between [1;2;3] and [3;2;1]\n";
163  cout << setw(7) << setprecision(3) << CrossProduct(p1,p2);
164  cout << "\n";
165 
166  cout << "\n";
167  cout << "Rotation matrix from quaternion\n";
168  ColumnVector axis(3); axis(1)=axis(2)=0; axis(3)=1.0;
169  Quaternion q(M_PI/4, axis);
170  cout << setw(7) << setprecision(3) << q.R();
171  cout << "\n";
172 
173  cout << "\n";
174  cout << "Transformation matrix from quaternion\n";
175  cout << setw(7) << setprecision(3) << q.T();
176 
177  cout << "\n";
178  cout << "Quaternion from rotation matrix\n";
179  Quaternion qq(q.R());
180  cout << setw(7) << setprecision(3) << qq.s() << endl;
181  cout << setw(7) << setprecision(3) << qq.v() << endl;
182  cout << "\n";
183 
184  cout << "\n";
185  cout << "Quaternion from transformation matrix\n";
186  qq = Quaternion(q.T());
187  cout << setw(7) << setprecision(3) << qq.s() << endl;
188  cout << setw(7) << setprecision(3) << qq.v() << endl;
189 }
190 
191 const Real RR_data[] =
192  {0, 0, 0, 1.0, 0, 0, 0, 0, 2.0,-0.5, 0, 0, 0, 0, 0, 0.1666666, 0, 0.1666666, 0, 0, 0, 0, 0,
193  0, 0, 0, 1.0, 0, 0, 0, 0, 1.0,-0.5, 0, 0, 0, 0, 0, 0.0833333, 0, 0.0833333, 0, 0, 0, 0, 0};
194 const Real RR_data_mdh[] =
195  {0, 0, 0, 1.0, 0, 0, 0, 0, 2.0, 0.5, 0, 0, 0, 0, 0, 0.1666666, 0, 0.1666666, 0, 0, 0, 0, 0,
196  0, 0, 0, 1.0, 0, 0, 0, 0, 1.0, 0.5, 0, 0, 0, 0, 0, 0.0833333, 0, 0.0833333, 0, 0, 0, 0, 0};
198  {0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0.0, 0, 0, 0, 0, 0, 0, 0.0, 1.666666, 0, 0, 0, 0, 0,
199  0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0.5, 0, 0, -0.25, 0, 0, 0, 0.0, 0.3333333, 0, 0, 0, 0, 0};
200 
201 const Real RP_data[] =
202  {0, 0, 0, 0, -M_PI/2.0, 0, 0, 0, 2.0, 0, 0, 0.0, 1.0, 0, 0, 1.0, 0, 1.0, 0, 0, 0, 0, 0,
203  1, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0,-1.0, 0.0833333, 0, 0, 0.0833333, 0, 0.0833333, 0, 0, 0, 0, 0};
205  {0, 0, 0, 0, M_PI/2.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.35, 0, 0, 0,
206  0, 0, 0, 0.4318, 0, 0, 0, 0, 17.4, -0.3638, 0.006, 0.2275, 0.13, 0, 0, 0.524, 0, 0.539, 0,
207  0, 0, 0.15005, 0.0203, -M_PI/2.0, 0, 0, 0, 4.8, -0.0203, -0.0141, 0.07, 0.066, 0, 0, 0.086, 0, 0.0125, 0,
208  0, 0, 0.4318, 0.0, M_PI/2.0, 0, 0, 0, 0.82, 0, 0.019, 0, 0.0018, 0, 0, 0.0013, 0, 0.0018, 0,
209  0, 0, 0, 0.0, -M_PI/2.0, 0, 0, 0, 0.34, 0.0, 0.0, 0.0, 0.0003, 0.0, 0.0, 0.0004, 0.0, 0.0003, 0,
210  0, 0, 0, 0, 0, 0, 0, 0, 0.09, 0.0, 0.0, 0.032, 0.00015, 0.0, 0.0, 0.00015, 0.0, 0.00004, 0};
212  {200e-6, -62.6111, 1.48e-3, (.395 +.435)/2, /* using + and - directions average */
213  200e-6, 107.815, .817e-3, (.126 + .071)/2,
214  200e-6, -53.7063, 1.38e-3, (.132 + .105)/2,
215  33e-6, 76.0364, 71.2e-6, (11.2e-3 + 16.9e-3)/2,
216  33e-6, 71.923, 82.6e-6, (9.26e-3 + 14.5e-3)/2,
217  33e-6, 76.686, 36.7e-6, (3.96e-3 + 10.5e-3)/2};
218 
220  {0.0, 0.0, 0.4120, 0.0, -M_PI/2, 0,0,0,9.29, 0.0, 0.0175, -0.1105, 0.276, 0.0, 0, 0.255, 0.0, 0.071,0,0,0,0,0,
221  0.0, 0.0, 0.1540, 0.0, M_PI/2.0, 0,0,0,5.01, 0.0, -1.054, 0.0, 0.108, 0.0, 0.0, 0.018, 0.0, 0.1,0,0,0,0,0,
222  1.0, -M_PI/2.0, 0.0, 0.0, 0.0, 0,0,0,4.25, 0.0, 0.0, -6.447, 2.51, 0.0, 0.0, 2.51, 0.0, 0.006,0,0,0,0,0,
223  0.0, 0.0, 0.0, 0.0, -M_PI/2.0, 0,0,0,1.08, 0.0, 0.092, -0.054, 0.002, 0.0, 0.0, 0.001, 0.0, 0.001,0,0,0,0,0,
224  0.0, 0.0, 0.0, 0.0, M_PI/2.0, 0,0,0,0.63, 0.0, 0.0, 0.566, 0.003, 0.0, 0.0, 0.003, 0.0, 0.0004,0,0,0,0,0,
225  0.0, 0.0, 0.2630, 0.0, 0.0, 0,0,0,0.51, 0.0, 0.0, 1.5540, 0.013, 0.0, 0.0, 0.013, 0.0, 0.0003,0,0,0,0,0};
226 
230 
232 {
233  int ndof;
234  ColumnVector q, qp, qpp; /* position, velocities and accelerations */
235  ColumnVector tau, dx; /* torque and state space error */
236  Matrix xd;
237 
238  ndof = robot.get_dof(); /* get the # of dof */
239  q = x.SubMatrix(1,ndof,1,1); /* position, velocities */
240  qp = x.SubMatrix(ndof+1,2*ndof,1,1); /* from state vector */
241  qpp = ColumnVector(ndof);
242  qpp = 0.0; /* set the vector to zero */
243  // tau = robot.torque(q0,qpp,qpp); /* compute the gravity torque */
244  tau = ColumnVector(ndof);
245  tau = 0.0;
246 
247  dx = (q-q0) & qp; /* compute dx using vertical concatenation */
248  tau = tau - K*dx; /* feedback correction */
249  qpp = robot.acceleration(q, qp, tau); /* acceleration */
250  xd = qp & qpp; /* state vector derivative */
251 
252  xd.Release(); return xd;
253 }
254 
255 void kinematics_demo(void)
256 {
257  Matrix initrob(2,23), Tobj;
258  ColumnVector qs, qr;
259  int dof = 0;
260  int i;
261 
262  cout << "\n";
263  cout << "=====================================================\n";
264  cout << "Robot RR kinematics\n";
265  cout << "=====================================================\n";
266  initrob << RR_data;
267  robot = Robot(initrob);
268  dof = robot.get_dof();
269 
270  cout << "\n";
271  cout << "Robot D-H parameters\n";
272  cout << " type theta d a alpha\n";
273  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
274  cout << "\n";
275  cout << "Robot joints variables\n";
276  cout << setw(7) << setprecision(3) << robot.get_q();
277  cout << "\n";
278  cout << "Robot position\n";
279  cout << setw(7) << setprecision(3) << robot.kine();
280  cout << "\n";
281  qr = ColumnVector(dof);
282  qr = M_PI/4.0;
283  robot.set_q(qr);
284  cout << "Robot joints variables\n";
285  cout << setw(7) << setprecision(3) << robot.get_q();
286  cout << "\n";
287  cout << "Robot position\n";
288  cout << setw(7) << setprecision(3) << robot.kine();
289  cout << "\n";
290  cout << "Robot Jacobian w/r to base frame\n";
291  cout << setw(7) << setprecision(3) << robot.jacobian();
292  cout << "\n";
293  cout << "Robot Jacobian w/r to tool frame\n";
294  cout << setw(7) << setprecision(3) << robot.jacobian(qr.Nrows());
295  cout << "\n";
296  for (i = 1; i <= qr.Nrows(); i++) {
297  cout << "Robot position partial derivative with respect to joint " << i << " \n";
298  cout << setw(7) << setprecision(3) << robot.dTdqi(i);
299  cout << "\n";
300  }
301  Tobj = robot.kine();
302  qs = ColumnVector(dof);
303  qs = M_PI/16.0;
304  robot.set_q(qs);
305  cout << "Robot inverse kinematics\n";
306  cout << " q start q final q real\n";
307  cout << setw(7) << setprecision(3) << (qs | robot.inv_kin(Tobj) | qr);
308  cout << "\n";
309  cout << "\n";
310 
311  cout << "=====================================================\n";
312  cout << "Robot RP kinematics\n";
313  cout << "=====================================================\n";
314  initrob << RP_data;
315  robot = Robot(initrob);
316  dof = robot.get_dof();
317  cout << "\n";
318  cout << "Robot D-H parameters\n";
319  cout << " type theta d a alpha\n";
320  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
321  cout << "\n";
322  cout << "Robot joints variables\n";
323  cout << setw(7) << setprecision(3) << robot.get_q();
324  cout << "\n";
325  cout << "Robot position\n";
326  cout << setw(7) << setprecision(3) << robot.kine();
327  cout << "\n";
328  robot.set_q(M_PI/4.0,1);
329  robot.set_q(4.0,2);
330  cout << "Robot joints variables\n";
331  cout << setw(7) << setprecision(3) << robot.get_q();
332  cout << "\n";
333  cout << "Robot position\n";
334  cout << setw(7) << setprecision(3) << robot.kine();
335  cout << "\n";
336  cout << "Robot Jacobian w/r to base frame\n";
337  cout << setw(7) << setprecision(3) << robot.jacobian();
338  cout << "\n";
339  qr = robot.get_q();
340  cout << "Robot Jacobian w/r to tool frame\n";
341  cout << setw(7) << setprecision(3) << robot.jacobian(qr.Nrows());
342  cout << "\n";
343  for (i = 1; i <= qr.Nrows(); i++) {
344  cout << "Robot position partial derivative with respect to joint " << i << " \n";
345  cout << setw(7) << setprecision(3) << robot.dTdqi(i);
346  cout << "\n";
347  }
348  Tobj = robot.kine();
349  robot.set_q(M_PI/16.0,1);
350  robot.set_q(1.0,2);
351  qs = robot.get_q();
352  cout << "Robot inverse kinematics\n";
353  cout << " q start q final q real\n";
354  cout << setw(7) << setprecision(3) << (qs | robot.inv_kin(Tobj) | qr);
355  cout << "\n";
356  cout << "\n";
357 
358  cout << "=====================================================\n";
359  cout << "Robot PUMA560 kinematics\n";
360  cout << "=====================================================\n";
361  robot = Robot("conf/puma560_dh.conf", "PUMA560_DH");
362  dof = robot.get_dof();
363  cout << "\n";
364  cout << "Robot joints variables\n";
365  cout << setw(7) << setprecision(3) << robot.get_q();
366  cout << "\n";
367  cout << "Robot position\n";
368  cout << setw(7) << setprecision(3) << robot.kine();
369  cout << "\n";
370  qr = ColumnVector(dof);
371  qr = M_PI/4.0;
372  robot.set_q(qr);
373  cout << "Robot joints variables\n";
374  cout << setw(7) << setprecision(3) << robot.get_q();
375  cout << "\n";
376  cout << "Robot position\n";
377  cout << setw(7) << setprecision(3) << robot.kine();
378  cout << "\n";
379  cout << "Robot Jacobian w/r to base frame\n";
380  cout << setw(7) << setprecision(3) << robot.jacobian();
381  cout << "\n";
382  cout << "Robot Jacobian w/r to tool frame\n";
383  cout << setw(7) << setprecision(3) << robot.jacobian(qr.Nrows());
384  cout << "\n";
385  for (i = 1; i <= qr.Nrows(); i++) {
386  cout << "Robot position partial derivative with respect to joint " << i << " \n";
387  cout << setw(7) << setprecision(3) << robot.dTdqi(i);
388  cout << "\n";
389  }
390  Tobj = robot.kine();
391  qs = ColumnVector(dof);
392  qs = 1.0;
393  qs(1) = M_PI/16.0;
394  robot.set_q(qs);
395  cout << "Robot inverse kinematics\n";
396  cout << " q start q final q real\n";
397  cout << setw(7) << setprecision(3) << (qs | robot.inv_kin(Tobj) | qr);
398  cout << "\n";
399  cout << "\n";
400  cout << "=====================================================\n";
401  cout << "Robot STANFORD kinematics\n";
402  cout << "=====================================================\n";
403  initrob = Matrix(6,23);
404  initrob << STANFORD_data;
405  robot = Robot(initrob);
406  dof = robot.get_dof();
407  cout << "\n";
408  cout << "Robot D-H parameters\n";
409  cout << " type theta d a alpha\n";
410  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
411  cout << "\n";
412  cout << "Robot joints variables\n";
413  cout << setw(7) << setprecision(3) << robot.get_q();
414  cout << "\n";
415  cout << "Robot position\n";
416  cout << setw(7) << setprecision(3) << robot.kine();
417  cout << "\n";
418  qr = ColumnVector(dof);
419  qr = M_PI/4.0;
420  robot.set_q(qr);
421  cout << "Robot joints variables\n";
422  cout << setw(7) << setprecision(3) << robot.get_q();
423  cout << "\n";
424  cout << "Robot position\n";
425  cout << setw(7) << setprecision(3) << robot.kine();
426  cout << "\n";
427  cout << "Robot Jacobian w/r to base frame\n";
428  cout << setw(7) << setprecision(3) << robot.jacobian();
429  cout << "\n";
430  cout << "Robot Jacobian w/r to tool frame\n";
431  cout << setw(7) << setprecision(3) << robot.jacobian(qr.Nrows());
432  cout << "\n";
433  for (i = 1; i <= qr.Nrows(); i++) {
434  cout << "Robot position partial derivative with respect to joint " << i << " \n";
435  cout << setw(7) << setprecision(3) << robot.dTdqi(i);
436  cout << "\n";
437  }
438  Tobj = robot.kine();
439  qs = ColumnVector(dof);
440  qs = 1.0;
441  qs(1) = M_PI/16.0;
442  robot.set_q(qs);
443  cout << "Robot inverse kinematics\n";
444  cout << " q start q final q real\n";
445  cout << setw(7) << setprecision(3) << (qs | robot.inv_kin(Tobj) | qr);
446  cout << "\n";
447  cout << "\n";
448 }
449 
450 void dynamics_demo(void)
451 {
452  int nok, nbad, dof = 0;
453  Matrix initrob(2,23), Tobj, xout;
454  ColumnVector qs, qr;
455  RowVector tout;
456  int i;
457 
458  cout << "\n";
459  cout << "=====================================================\n";
460  cout << "Robot RR dynamics\n";
461  cout << "=====================================================\n";
462  initrob << RR_data;
463  robot = Robot(initrob);
464  dof = robot.get_dof();
465  cout << "\n";
466  cout << "Robot D-H parameters\n";
467  cout << " type theta d a alpha\n";
468  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
469  cout << "\n";
470  cout << "Robot D-H inertial parameters\n";
471  cout << " mass cx cy cz Ixx Ixy Ixz Iyy Iyz Izz\n";
472  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,9,18);
473  cout << "\n";
474  cout << "Robot joints variables\n";
475  cout << setw(7) << setprecision(3) << robot.get_q();
476  cout << "\n";
477  cout << "Robot Inertia matrix\n";
478  cout << setw(7) << setprecision(3) << robot.inertia(robot.get_q());
479  cout << "\n";
480 
481  K = Matrix(dof,2*dof);
482  K = 0.0;
483  K(1,1) = K(2,2) = 25.0; /* K = [25I 7.071I ] */
484  K(1,3) = K(2,4) = 7.071;
485  cout << "Feedback gain matrix K\n";
486  cout << setw(7) << setprecision(3) << K;
487  cout << "\n";
488  q0 = ColumnVector(dof);
489  q0 = M_PI/4.0;
490  qs = ColumnVector(2*dof);
491  qs = 0.0;
492 
493  cout << " time ";
494  for(i = 1; i <= dof; i++)
495  cout <<"q" << i << " ";
496  for(i = 1; i <= dof; i++)
497  cout <<"qp" << i << " ";
498  cout << endl;
499 
500  /* Runge_Kutta4(xdot, qs, 0.0, 4.0, 160, tout, xout);
501  replaced by adaptive step size */
502  odeint(xdot, qs, 0.0, 4.0, 1e-4,0.1, 1e-12, nok, nbad, tout, xout, 0.05);
503  cout << setw(7) << setprecision(3) << (tout & xout).t();
504  cout << "\n";
505  cout << "\n";
506 
507 
508  set_plot2d("Robot joints position", "time (sec)", "q(i) (rad)", "q", DATAPOINTS,
509  tout, xout, 1, dof);
510 
511  /* uncomment the following two lines to obtain a
512  ps file of the graph */
513  /* plotposition.addcommand("set term post");
514  plotposition.addcommand("set output \"demo.ps\"");*/
515 
516  set_plot2d("Robot joints velocity", "time (sec)", "qp(i) (rad/s)", "qp", DATAPOINTS,
517  tout, xout, dof+1, 2*dof);
518 
519 
520  cout << "=====================================================\n";
521  cout << "Robot RP dynamics\n";
522  cout << "=====================================================\n";
523  initrob << RP_data;
524  robot = Robot(initrob);
525  dof = robot.get_dof();
526  cout << "\n";
527  cout << "Robot D-H parameters\n";
528  cout << " type theta d a alpha\n";
529  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
530  cout << "\n";
531  cout << "Robot D-H inertial parameters\n";
532  cout << " mass cx cy cz Ixx Ixy Ixz Iyy Iyz Izz\n";
533  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,9,18);
534  cout << "\n";
535  cout << "Robot joints variables\n";
536  cout << setw(7) << setprecision(3) << robot.get_q();
537  cout << "\n";
538  cout << "Robot Inertia matrix\n";
539  cout << setw(7) << setprecision(3) << robot.inertia(robot.get_q());
540  cout << "\n";
541  cout << "\n";
542 
543  cout << "=====================================================\n";
544  cout << "Robot PUMA560 dynamics\n";
545  cout << "=====================================================\n";
546  initrob = Matrix(6,19);
547  initrob << PUMA560_data;
548  Matrix temp(6,4);
549  temp = 0; /* empty motor dynamics */
550  robot = Robot((initrob | temp));
551  dof = robot.get_dof();
552  cout << "\n";
553  cout << "Robot D-H parameters\n";
554  cout << " type theta d a alpha\n";
555  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
556  cout << "\n";
557  cout << "Robot D-H inertial parameters\n";
558  cout << " mass cx cy cz Ixx Ixy Ixz Iyy Iyz Izz\n";
559  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,9,18);
560  cout << "\n";
561  cout << "Robot joints variables\n";
562  cout << setw(7) << setprecision(3) << robot.get_q();
563  cout << "\n";
564  cout << "Robot Inertia matrix\n";
565  cout << setw(8) << setprecision(4) << robot.inertia(robot.get_q());
566  cout << "\n";
567  qs = ColumnVector(dof);
568  qr = ColumnVector(dof);
569  qs =0.0;
570  qr =0.0;
571  cout << "Robot Torque\n";
572  cout << setw(8) << setprecision(4) << robot.torque(robot.get_q(),qs,qr);
573  cout << "\n";
574  cout << "Robot acceleration\n";
575  cout << setw(8) << setprecision(4) << robot.acceleration(robot.get_q(),qs,qr);
576  cout << "\n";
577 
578  cout << "\n";
579  cout << "=====================================================\n";
580  cout << "Robot STANFORD dynamics\n";
581  cout << "=====================================================\n";
582  initrob = Matrix(6,23);
583  initrob << STANFORD_data;
584  robot = Robot(initrob);
585  dof = robot.get_dof();
586  cout << "\n";
587  cout << "Robot D-H parameters\n";
588  cout << " type theta d a alpha\n";
589  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
590  cout << "\n";
591  cout << "Robot D-H inertial parameters\n";
592  cout << " mass cx cy cz Ixx Ixy Ixz Iyy Iyz Izz\n";
593  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,9,18);
594  cout << "\n";
595  cout << "Robot joints variables\n";
596  cout << setw(7) << setprecision(3) << robot.get_q();
597  cout << "\n";
598  cout << "Robot Inertia matrix\n";
599  cout << setw(7) << setprecision(3) << robot.inertia(robot.get_q());
600  cout << "\n";
601  cout << "\n";
602 
603  cout << "=====================================================\n";
604  cout << "Robot PUMA560 with motors dynamics\n";
605  cout << "=====================================================\n";
606  initrob = Matrix(6,19);
607  initrob << PUMA560_data;
608  Matrix initrobm = Matrix(6,4);
609  initrobm << PUMA560_motor;
610  robot = Robot(initrob,initrobm);
611  dof =robot.get_dof();
612  cout << "\n";
613  cout << "Robot D-H parameters\n";
614  cout << " type theta d a alpha\n";
615  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,1,5);
616  cout << "\n";
617  cout << "Robot D-H inertial parameters\n";
618  cout << " mass cx cy cz Ixx Ixy Ixz Iyy Iyz Izz\n";
619  cout << setw(7) << setprecision(3) << initrob.SubMatrix(1,dof,9,18);
620  cout << "\n";
621  cout << "Robot motors inertia, gear ratio, viscous and Coulomb friction coefficients\n";
622  cout << " Im Gr B Cf\n";
623  cout << setw(7) << setprecision(3) << initrobm;
624  cout << "\n";
625  cout << "Robot joints variables\n";
626  cout << setw(7) << setprecision(3) << robot.get_q();
627  cout << "\n";
628  cout << "Robot Inertia matrix\n";
629  cout << setw(8) << setprecision(4) << robot.inertia(robot.get_q());
630  cout << "\n";
631  qs = ColumnVector(dof);
632  qr = ColumnVector(dof);
633  qs =0.0;
634  qr =0.0;
635  robot.set_q(qs);
636  cout << "Robot Torque\n";
637  cout << setw(8) << setprecision(4) << robot.torque(robot.get_q(),qs,qr);
638  cout << "\n";
639  cout << "Robot acceleration\n";
640  cout << setw(8) << setprecision(4) << robot.acceleration(robot.get_q(),qs,qr);
641  cout << "\n";
642 }
Quaternion class definition.
Definition: quaternion.h:92
ReturnMatrix R() const
Rotation matrix from a unit quaternion.
Definition: quaternion.cpp:458
short set_plot2d(const char *title_graph, const char *x_axis_title, const char *y_axis_title, const char *label, LineType_en enLineType, const Matrix &xdata, const Matrix &ydata, int start_y, int end_y)
Definition: gnugraph.cpp:793
void Release()
Definition: newmat.h:514
int get_dof() const
Return dof.
Definition: robot.h:240
DH notation robot class.
Definition: robot.h:340
const Real STANFORD_data[]
Definition: demo.cpp:219
const Real RR_data_mdh_min_para[]
Definition: demo.cpp:197
ReturnMatrix rotd(const Real theta, const ColumnVector &k1, const ColumnVector &k2)
Rotation around an arbitrary line.
Definition: homogen.cpp:240
virtual ReturnMatrix torque(const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp)
Joint torque, without contact force, based on Recursive Newton-Euler formulation. ...
Definition: dynamics.cpp:135
const Real RP_data[]
Definition: demo.cpp:201
ReturnMatrix trans(const ColumnVector &a)
Translation.
Definition: homogen.cpp:68
Robots class definitions.
ReturnMatrix rpy(const ColumnVector &a)
Roll Pitch Yaw rotation.
Definition: homogen.cpp:182
Matrix K
Definition: demo.cpp:228
double Real
Definition: include.h:307
static const char rcsid[]
RCS/CVS version.
Definition: demo.cpp:63
int main(void)
Definition: demo.cpp:79
const Real PUMA560_motor[]
Definition: demo.cpp:211
const Real RR_data_mdh[]
Definition: demo.cpp:194
int Nrows() const
Definition: newmat.h:494
Utility header file.
Real s() const
Return scalar part.
Definition: quaternion.h:119
ReturnMatrix inertia(const ColumnVector &q)
Inertia of the manipulator.
Definition: dynamics.cpp:83
ReturnMatrix acceleration(const ColumnVector &q, const ColumnVector &qp, const ColumnVector &tau)
Joints acceleration without contact force.
Definition: dynamics.cpp:100
virtual void dTdqi(Matrix &dRot, ColumnVector &dp, const int i)
Partial derivative of the robot position (homogeneous transf.)
Definition: kinemat.cpp:249
ReturnMatrix rotx(const Real alpha)
Rotation around x axis.
Definition: homogen.cpp:87
void set_q(const ColumnVector &q)
Set the joint position vector.
Definition: robot.cpp:1137
ReturnMatrix irotk(const Matrix &R)
Obtain axis from a rotation matrix.
Definition: homogen.cpp:253
ReturnMatrix ieulzxz(const Matrix &R)
Obtain Roll, Pitch and Yaw from a rotation matrix.
Definition: homogen.cpp:294
ReturnMatrix rotz(const Real gamma)
Rotation around z axis.
Definition: homogen.cpp:127
ColumnVector q0
Definition: demo.cpp:229
Matrix CrossProduct(const Matrix &A, const Matrix &B)
Definition: newmat.h:2062
const Real PUMA560_data[]
Definition: demo.cpp:204
void homogen_demo(void)
Definition: demo.cpp:95
The usual rectangular matrix.
Definition: newmat.h:625
Quaternion class.
ReturnMatrix roty(const Real beta)
Rotation around x axis.
Definition: homogen.cpp:107
ReturnMatrix irpy(const Matrix &R)
Obtain Roll, Pitch and Yaw from a rotation matrix.
Definition: homogen.cpp:271
Header file for graphics definitions.
void dynamics_demo(void)
Definition: demo.cpp:450
void kine(Matrix &Rot, ColumnVector &pos) const
Direct kinematics at end effector.
Definition: kinemat.cpp:92
GetSubMatrix SubMatrix(int fr, int lr, int fc, int lc) const
Definition: newmat.h:2146
void kinematics_demo(void)
Definition: demo.cpp:255
ReturnMatrix xdot(Real t, const Matrix &x)
Definition: demo.cpp:231
void odeint(ReturnMatrix(*xdot)(Real time, const Matrix &xin), Matrix &xo, Real to, Real tf, Real eps, Real h1, Real hmin, int &nok, int &nbad, RowVector &tout, Matrix &xout, Real dtsav)
Integrate the ordinary differential equation xdot from time to to time tf using an adaptive step size...
Definition: utils.cpp:347
ReturnMatrix eulzxz(const ColumnVector &a)
Euler ZXZ rotation.
Definition: homogen.cpp:211
Row vector.
Definition: newmat.h:953
const Real RR_data[]
Definition: demo.cpp:191
Column vector.
Definition: newmat.h:1008
ReturnMatrix inv_kin(const Matrix &Tobj, const int mj=0)
Overload inv_kin function.
Definition: invkine.cpp:218
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
Definition: robot.h:357
ReturnMatrix T() const
Transformation matrix from a quaternion.
Definition: quaternion.cpp:499
Real get_q(const int i) const
Definition: robot.h:235
Robot robot
Definition: demo.cpp:227
ReturnMatrix rotk(const Real theta, const ColumnVector &k)
Rotation around arbitrary axis.
Definition: homogen.cpp:149


kni
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:44