62 static const char rcsid[] =
"$Id: demo.cpp,v 1.34 2006/05/16 16:27:43 gourdeau Exp $";
71 using namespace ROBOOP;
81 cout <<
"=====================================================\n";
82 cout <<
" ROBOOP -- A robotics object oriented package in C++ \n";;
83 cout <<
" DEMO program \n";
84 cout <<
"=====================================================\n";
98 Real ott[] = {1.0,2.0,3.0};
99 Real tto[] = {3.0,2.0,1.0};
102 cout <<
"=====================================================\n";
103 cout <<
"Homogeneous transformations\n";
104 cout <<
"=====================================================\n";
106 cout <<
"Translation of [1;2;3]\n";
108 cout << setw(7) << setprecision(3) <<
trans(p1);
111 cout <<
"Rotation of pi/6 around axis X\n";
112 cout << setw(7) << setprecision(3) <<
rotx(
M_PI/6);
116 cout <<
"Rotation of pi/8 around axis Y\n";
117 cout << setw(7) << setprecision(3) <<
roty(
M_PI/8);
121 cout <<
"Rotation of pi/3 around axis Z\n";
122 cout << setw(7) << setprecision(3) <<
rotz(
M_PI/3);
126 cout <<
"Rotation of pi/3 around axis [1;2;3]\n";
127 cout << setw(7) << setprecision(3) <<
rotk(
M_PI/3,p1);
131 cout <<
"Rotation of pi/6 around line [1;2;3] -- [3;2;1]\n";
133 cout << setw(7) << setprecision(3) <<
rotd(
M_PI/3,p1,p2);
137 cout <<
"Roll Pitch Yaw Rotation [1;2;3]\n";
138 cout << setw(7) << setprecision(3) <<
rpy(p1);
142 cout <<
"Euler ZXZ Rotation [3;2;1]\n";
143 cout << setw(7) << setprecision(3) <<
eulzxz(p2);
147 cout <<
"Inverse of Rotation around axis\n";
148 cout << setw(7) << setprecision(3) <<
irotk(
rotk(
M_PI/3,p1));
152 cout <<
"Inverse of Roll Pitch Yaw Rotation\n";
153 cout << setw(7) << setprecision(3) <<
irpy(
rpy(p1));
157 cout <<
"Inverse of Euler ZXZ Rotation\n";
162 cout <<
"Cross product between [1;2;3] and [3;2;1]\n";
163 cout << setw(7) << setprecision(3) <<
CrossProduct(p1,p2);
167 cout <<
"Rotation matrix from quaternion\n";
170 cout << setw(7) << setprecision(3) << q.
R();
174 cout <<
"Transformation matrix from quaternion\n";
175 cout << setw(7) << setprecision(3) << q.
T();
178 cout <<
"Quaternion from rotation matrix\n";
180 cout << setw(7) << setprecision(3) << qq.
s() << endl;
181 cout << setw(7) << setprecision(3) << qq.v() << endl;
185 cout <<
"Quaternion from transformation matrix\n";
187 cout << setw(7) << setprecision(3) << qq.
s() << endl;
188 cout << setw(7) << setprecision(3) << qq.v() << endl;
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};
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};
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,
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};
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};
257 Matrix initrob(2,23), Tobj;
263 cout <<
"=====================================================\n";
264 cout <<
"Robot RR kinematics\n";
265 cout <<
"=====================================================\n";
267 robot =
Robot(initrob);
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);
275 cout <<
"Robot joints variables\n";
276 cout << setw(7) << setprecision(3) << robot.
get_q();
278 cout <<
"Robot position\n";
279 cout << setw(7) << setprecision(3) << robot.
kine();
284 cout <<
"Robot joints variables\n";
285 cout << setw(7) << setprecision(3) << robot.
get_q();
287 cout <<
"Robot position\n";
288 cout << setw(7) << setprecision(3) << robot.
kine();
290 cout <<
"Robot Jacobian w/r to base frame\n";
291 cout << setw(7) << setprecision(3) << robot.
jacobian();
293 cout <<
"Robot Jacobian w/r to tool frame\n";
294 cout << setw(7) << setprecision(3) << robot.
jacobian(qr.
Nrows());
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);
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);
311 cout <<
"=====================================================\n";
312 cout <<
"Robot RP kinematics\n";
313 cout <<
"=====================================================\n";
315 robot =
Robot(initrob);
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);
322 cout <<
"Robot joints variables\n";
323 cout << setw(7) << setprecision(3) << robot.
get_q();
325 cout <<
"Robot position\n";
326 cout << setw(7) << setprecision(3) << robot.
kine();
330 cout <<
"Robot joints variables\n";
331 cout << setw(7) << setprecision(3) << robot.
get_q();
333 cout <<
"Robot position\n";
334 cout << setw(7) << setprecision(3) << robot.
kine();
336 cout <<
"Robot Jacobian w/r to base frame\n";
337 cout << setw(7) << setprecision(3) << robot.
jacobian();
340 cout <<
"Robot Jacobian w/r to tool frame\n";
341 cout << setw(7) << setprecision(3) << robot.
jacobian(qr.
Nrows());
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);
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);
358 cout <<
"=====================================================\n";
359 cout <<
"Robot PUMA560 kinematics\n";
360 cout <<
"=====================================================\n";
361 robot =
Robot(
"conf/puma560_dh.conf",
"PUMA560_DH");
364 cout <<
"Robot joints variables\n";
365 cout << setw(7) << setprecision(3) << robot.
get_q();
367 cout <<
"Robot position\n";
368 cout << setw(7) << setprecision(3) << robot.
kine();
373 cout <<
"Robot joints variables\n";
374 cout << setw(7) << setprecision(3) << robot.
get_q();
376 cout <<
"Robot position\n";
377 cout << setw(7) << setprecision(3) << robot.
kine();
379 cout <<
"Robot Jacobian w/r to base frame\n";
380 cout << setw(7) << setprecision(3) << robot.
jacobian();
382 cout <<
"Robot Jacobian w/r to tool frame\n";
383 cout << setw(7) << setprecision(3) << robot.
jacobian(qr.
Nrows());
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);
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);
400 cout <<
"=====================================================\n";
401 cout <<
"Robot STANFORD kinematics\n";
402 cout <<
"=====================================================\n";
405 robot =
Robot(initrob);
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);
412 cout <<
"Robot joints variables\n";
413 cout << setw(7) << setprecision(3) << robot.
get_q();
415 cout <<
"Robot position\n";
416 cout << setw(7) << setprecision(3) << robot.
kine();
421 cout <<
"Robot joints variables\n";
422 cout << setw(7) << setprecision(3) << robot.
get_q();
424 cout <<
"Robot position\n";
425 cout << setw(7) << setprecision(3) << robot.
kine();
427 cout <<
"Robot Jacobian w/r to base frame\n";
428 cout << setw(7) << setprecision(3) << robot.
jacobian();
430 cout <<
"Robot Jacobian w/r to tool frame\n";
431 cout << setw(7) << setprecision(3) << robot.
jacobian(qr.
Nrows());
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);
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);
452 int nok, nbad, dof = 0;
453 Matrix initrob(2,23), Tobj, xout;
459 cout <<
"=====================================================\n";
460 cout <<
"Robot RR dynamics\n";
461 cout <<
"=====================================================\n";
463 robot =
Robot(initrob);
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);
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);
474 cout <<
"Robot joints variables\n";
475 cout << setw(7) << setprecision(3) << robot.
get_q();
477 cout <<
"Robot Inertia matrix\n";
478 cout << setw(7) << setprecision(3) << robot.
inertia(robot.
get_q());
483 K(1,1) =
K(2,2) = 25.0;
484 K(1,3) =
K(2,4) = 7.071;
485 cout <<
"Feedback gain matrix K\n";
486 cout << setw(7) << setprecision(3) <<
K;
494 for(i = 1; i <= dof; i++)
495 cout <<
"q" << i <<
" ";
496 for(i = 1; i <= dof; i++)
497 cout <<
"qp" << i <<
" ";
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();
517 tout, xout, dof+1, 2*dof);
520 cout <<
"=====================================================\n";
521 cout <<
"Robot RP dynamics\n";
522 cout <<
"=====================================================\n";
524 robot =
Robot(initrob);
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);
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);
535 cout <<
"Robot joints variables\n";
536 cout << setw(7) << setprecision(3) << robot.
get_q();
538 cout <<
"Robot Inertia matrix\n";
539 cout << setw(7) << setprecision(3) << robot.
inertia(robot.
get_q());
543 cout <<
"=====================================================\n";
544 cout <<
"Robot PUMA560 dynamics\n";
545 cout <<
"=====================================================\n";
550 robot =
Robot((initrob | temp));
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);
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);
561 cout <<
"Robot joints variables\n";
562 cout << setw(7) << setprecision(3) << robot.
get_q();
564 cout <<
"Robot Inertia matrix\n";
565 cout << setw(8) << setprecision(4) << robot.
inertia(robot.
get_q());
571 cout <<
"Robot Torque\n";
572 cout << setw(8) << setprecision(4) << robot.
torque(robot.
get_q(),qs,qr);
574 cout <<
"Robot acceleration\n";
579 cout <<
"=====================================================\n";
580 cout <<
"Robot STANFORD dynamics\n";
581 cout <<
"=====================================================\n";
584 robot =
Robot(initrob);
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);
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);
595 cout <<
"Robot joints variables\n";
596 cout << setw(7) << setprecision(3) << robot.
get_q();
598 cout <<
"Robot Inertia matrix\n";
599 cout << setw(7) << setprecision(3) << robot.
inertia(robot.
get_q());
603 cout <<
"=====================================================\n";
604 cout <<
"Robot PUMA560 with motors dynamics\n";
605 cout <<
"=====================================================\n";
610 robot =
Robot(initrob,initrobm);
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);
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);
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;
625 cout <<
"Robot joints variables\n";
626 cout << setw(7) << setprecision(3) << robot.
get_q();
628 cout <<
"Robot Inertia matrix\n";
629 cout << setw(8) << setprecision(4) << robot.
inertia(robot.
get_q());
636 cout <<
"Robot Torque\n";
637 cout << setw(8) << setprecision(4) << robot.
torque(robot.
get_q(),qs,qr);
639 cout <<
"Robot acceleration\n";
Quaternion class definition.
ReturnMatrix R() const
Rotation matrix from a unit quaternion.
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)
int get_dof() const
Return dof.
const Real STANFORD_data[]
const Real RR_data_mdh_min_para[]
ReturnMatrix rotd(const Real theta, const ColumnVector &k1, const ColumnVector &k2)
Rotation around an arbitrary line.
virtual ReturnMatrix torque(const ColumnVector &q, const ColumnVector &qp, const ColumnVector &qpp)
Joint torque, without contact force, based on Recursive Newton-Euler formulation. ...
ReturnMatrix trans(const ColumnVector &a)
Translation.
Robots class definitions.
ReturnMatrix rpy(const ColumnVector &a)
Roll Pitch Yaw rotation.
static const char rcsid[]
RCS/CVS version.
const Real PUMA560_motor[]
Real s() const
Return scalar part.
ReturnMatrix inertia(const ColumnVector &q)
Inertia of the manipulator.
ReturnMatrix acceleration(const ColumnVector &q, const ColumnVector &qp, const ColumnVector &tau)
Joints acceleration without contact force.
virtual void dTdqi(Matrix &dRot, ColumnVector &dp, const int i)
Partial derivative of the robot position (homogeneous transf.)
ReturnMatrix rotx(const Real alpha)
Rotation around x axis.
void set_q(const ColumnVector &q)
Set the joint position vector.
ReturnMatrix irotk(const Matrix &R)
Obtain axis from a rotation matrix.
ReturnMatrix ieulzxz(const Matrix &R)
Obtain Roll, Pitch and Yaw from a rotation matrix.
ReturnMatrix rotz(const Real gamma)
Rotation around z axis.
Matrix CrossProduct(const Matrix &A, const Matrix &B)
const Real PUMA560_data[]
The usual rectangular matrix.
ReturnMatrix roty(const Real beta)
Rotation around x axis.
ReturnMatrix irpy(const Matrix &R)
Obtain Roll, Pitch and Yaw from a rotation matrix.
Header file for graphics definitions.
void kine(Matrix &Rot, ColumnVector &pos) const
Direct kinematics at end effector.
GetSubMatrix SubMatrix(int fr, int lr, int fc, int lc) const
void kinematics_demo(void)
ReturnMatrix xdot(Real t, const Matrix &x)
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...
ReturnMatrix eulzxz(const ColumnVector &a)
Euler ZXZ rotation.
ReturnMatrix inv_kin(const Matrix &Tobj, const int mj=0)
Overload inv_kin function.
virtual ReturnMatrix jacobian(const int ref=0) const
Jacobian of mobile links expressed at frame ref.
ReturnMatrix T() const
Transformation matrix from a quaternion.
Real get_q(const int i) const
ReturnMatrix rotk(const Real theta, const ColumnVector &k)
Rotation around arbitrary axis.