Visual Servoing Platform  version 3.0.0
vpRobotAfma6.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Interface for the Irisa's Afma6 robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #include <visp3/core/vpConfig.h>
39 
40 #ifdef VISP_HAVE_AFMA6
41 
42 #include <signal.h>
43 #include <stdlib.h>
44 #include <sys/types.h>
45 #include <unistd.h>
46 
47 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpExponentialMap.h>
49 #include <visp3/core/vpDebug.h>
50 #include <visp3/core/vpVelocityTwistMatrix.h>
51 #include <visp3/core/vpThetaUVector.h>
52 #include <visp3/robot/vpRobotAfma6.h>
53 #include <visp3/core/vpRotationMatrix.h>
54 
55 /* ---------------------------------------------------------------------- */
56 /* --- STATIC ----------------------------------------------------------- */
57 /* ---------------------------------------------------------------------- */
58 
59 bool vpRobotAfma6::robotAlreadyCreated = false;
60 
69 
70 /* ---------------------------------------------------------------------- */
71 /* --- EMERGENCY STOP --------------------------------------------------- */
72 /* ---------------------------------------------------------------------- */
73 
81 void emergencyStopAfma6(int signo)
82 {
83  std::cout << "Stop the Afma6 application by signal ("
84  << signo << "): " << (char)7 ;
85  switch(signo)
86  {
87  case SIGINT:
88  std::cout << "SIGINT (stop by ^C) " << std::endl ; break ;
89  case SIGBUS:
90  std::cout <<"SIGBUS (stop due to a bus error) " << std::endl ; break ;
91  case SIGSEGV:
92  std::cout <<"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
93  case SIGKILL:
94  std::cout <<"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
95  case SIGQUIT:
96  std::cout <<"SIGQUIT " << std::endl ; break ;
97  default :
98  std::cout << signo << std::endl ;
99  }
100  //std::cout << "Emergency stop called\n";
101  // PrimitiveESTOP_Afma6();
102  PrimitiveSTOP_Afma6();
103  std::cout << "Robot was stopped\n";
104 
105  // Free allocated resources
106  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
107 
108  fprintf(stdout, "Application ");
109  fflush(stdout);
110  kill(getpid(), SIGKILL);
111  exit(1) ;
112 }
113 
114 /* ---------------------------------------------------------------------- */
115 /* --- CONSTRUCTOR ------------------------------------------------------ */
116 /* ---------------------------------------------------------------------- */
117 
154 vpRobotAfma6::vpRobotAfma6 (bool verbose)
155  :
156  vpAfma6 (),
157  vpRobot ()
158 {
159 
160  /*
161  #define SIGHUP 1 // hangup
162  #define SIGINT 2 // interrupt (rubout)
163  #define SIGQUIT 3 // quit (ASCII FS)
164  #define SIGILL 4 // illegal instruction (not reset when caught)
165  #define SIGTRAP 5 // trace trap (not reset when caught)
166  #define SIGIOT 6 // IOT instruction
167  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
168  #define SIGEMT 7 // EMT instruction
169  #define SIGFPE 8 // floating point exception
170  #define SIGKILL 9 // kill (cannot be caught or ignored)
171  #define SIGBUS 10 // bus error
172  #define SIGSEGV 11 // segmentation violation
173  #define SIGSYS 12 // bad argument to system call
174  #define SIGPIPE 13 // write on a pipe with no one to read it
175  #define SIGALRM 14 // alarm clock
176  #define SIGTERM 15 // software termination signal from kill
177  */
178 
179  signal(SIGINT, emergencyStopAfma6);
180  signal(SIGBUS, emergencyStopAfma6) ;
181  signal(SIGSEGV, emergencyStopAfma6) ;
182  signal(SIGKILL, emergencyStopAfma6);
183  signal(SIGQUIT, emergencyStopAfma6);
184 
185  setVerbose(verbose);
186  if (verbose_)
187  std::cout << "Open communication with MotionBlox.\n";
188  try {
189  this->init();
191  }
192  catch(...) {
193  // vpERROR_TRACE("Error caught") ;
194  throw ;
195  }
196  positioningVelocity = defaultPositioningVelocity ;
197 
198  vpRobotAfma6::robotAlreadyCreated = true;
199 
200  return ;
201 }
202 
203 
204 /* ------------------------------------------------------------------------ */
205 /* --- INITIALISATION ----------------------------------------------------- */
206 /* ------------------------------------------------------------------------ */
207 
227 void
229 {
230  InitTry;
231 
232  // Initialise private variables used to compute the measured velocities
233  q_prev_getvel.resize(6);
234  q_prev_getvel = 0;
235  time_prev_getvel = 0;
236  first_time_getvel = true;
237 
238  // Initialise private variables used to compute the measured displacement
239  q_prev_getdis.resize(6);
240  q_prev_getdis = 0;
241  first_time_getdis = true;
242 
243  // Initialize the firewire connection
244  Try( InitializeConnection(verbose_) );
245 
246  // Connect to the servoboard using the servo board GUID
247  Try( InitializeNode_Afma6() );
248 
249  Try( PrimitiveRESET_Afma6() );
250 
251  // Update the eMc matrix in the low level controller
253 
254  // Look if the power is on or off
255  UInt32 HIPowerStatus;
256  UInt32 EStopStatus;
257  Try( PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
258  &HIPowerStatus));
259  CAL_Wait(0.1);
260 
261  // Print the robot status
262  if (verbose_) {
263  std::cout << "Robot status: ";
264  switch(EStopStatus) {
265  case ESTOP_AUTO:
266  case ESTOP_MANUAL:
267  if (HIPowerStatus == 0)
268  std::cout << "Power is OFF" << std::endl;
269  else
270  std::cout << "Power is ON" << std::endl;
271  break;
272  case ESTOP_ACTIVATED:
273  std::cout << "Emergency stop is activated" << std::endl;
274  break;
275  default:
276  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
277  std::cout << "You have to call Adept for maintenance..." << std::endl;
278  // Free allocated resources
279  }
280  std::cout << std::endl;
281  }
282  // get real joint min/max from the MotionBlox
283  Try( PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max) );
284 // for (unsigned int i=0; i < njoint; i++) {
285 // printf("axis %d: joint min %lf, max %lf\n", i, _joint_min[i], _joint_max[i]);
286 // }
287 
288  // If an error occur in the low level controller, goto here
289  //CatchPrint();
290  Catch();
291 
292  // Test if an error occurs
293  if (TryStt == -20001)
294  printf("No connection detected. Check if the robot is powered on \n"
295  "and if the firewire link exist between the MotionBlox and this computer.\n");
296  else if (TryStt == -675)
297  printf(" Timeout enabling power...\n");
298 
299  if (TryStt < 0) {
300  // Power off the robot
301  PrimitivePOWEROFF_Afma6();
302  // Free allocated resources
303  ShutDownConnection();
304 
305  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
307  "Cannot open connexion with the motionblox");
308  }
309  return ;
310 }
311 
348 void
351 {
352 
353  InitTry;
354  // Read the robot constants from files
355  // - joint [min,max], coupl_56, long_56
356  // - camera extrinsic parameters relative to eMc
357  vpAfma6::init(tool, projModel);
358 
359  // Set the robot constant (coupl_56, long_56) in the MotionBlox
360  Try( PrimitiveROBOT_CONST_Afma6(_coupl_56, _long_56) );
361 
362  // Set the camera constant (eMc pose) in the MotionBlox
363  double eMc_pose[6];
364  for (unsigned int i=0; i < 3; i ++) {
365  eMc_pose[i] = _etc[i]; // translation in meters
366  eMc_pose[i+3] = _erc[i]; // rotation in rad
367  }
368  // Update the eMc pose in the low level controller
369  Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
370 
371  // get real joint min/max from the MotionBlox
372  Try( PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max) );
373 // for (unsigned int i=0; i < njoint; i++) {
374 // printf("axis %d: joint min %lf, max %lf\n", i, _joint_min[i], _joint_max[i]);
375 // }
376 
377  setToolType(tool);
378 
379  CatchPrint();
380  return ;
381 }
382 
383 /* ------------------------------------------------------------------------ */
384 /* --- DESTRUCTOR --------------------------------------------------------- */
385 /* ------------------------------------------------------------------------ */
386 
394 {
395  InitTry;
396 
398 
399  // Look if the power is on or off
400  UInt32 HIPowerStatus;
401  Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
402  &HIPowerStatus));
403  CAL_Wait(0.1);
404 
405 // if (HIPowerStatus == 1) {
406 // fprintf(stdout, "Power OFF the robot\n");
407 // fflush(stdout);
408 
409 // Try( PrimitivePOWEROFF_Afma6() );
410 // }
411 
412  // Free allocated resources
413  ShutDownConnection();
414 
415  vpRobotAfma6::robotAlreadyCreated = false;
416 
417  CatchPrint();
418  return;
419 }
420 
421 
422 
423 
432 {
433  InitTry;
434 
435  switch (newState) {
436  case vpRobot::STATE_STOP: {
438  Try( PrimitiveSTOP_Afma6() );
439  }
440  break;
441  }
444  std::cout << "Change the control mode from velocity to position control.\n";
445  Try( PrimitiveSTOP_Afma6() );
446  }
447  else {
448  //std::cout << "Change the control mode from stop to position control.\n";
449  }
450  this->powerOn();
451  break;
452  }
455  std::cout << "Change the control mode from stop to velocity control.\n";
456  }
457  this->powerOn();
458  break;
459  }
460  default:
461  break ;
462  }
463 
464  CatchPrint();
465 
466  return vpRobot::setRobotState (newState);
467 }
468 
469 
470 /* ------------------------------------------------------------------------ */
471 /* --- STOP --------------------------------------------------------------- */
472 /* ------------------------------------------------------------------------ */
473 
481 void
483 {
484  InitTry;
485  Try( PrimitiveSTOP_Afma6() );
487 
488  CatchPrint();
489  if (TryStt < 0) {
490  vpERROR_TRACE ("Cannot stop robot motion");
492  "Cannot stop robot motion.");
493  }
494 }
495 
505 void
507 {
508  InitTry;
509 
510  // Look if the power is on or off
511  UInt32 HIPowerStatus;
512  UInt32 EStopStatus;
513  bool firsttime = true;
514  unsigned int nitermax = 10;
515 
516  for (unsigned int i=0; i<nitermax; i++) {
517  Try( PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
518  &HIPowerStatus));
519  if (EStopStatus == ESTOP_AUTO) {
520  break; // exit for loop
521  }
522  else if (EStopStatus == ESTOP_MANUAL) {
523  break; // exit for loop
524  }
525  else if (EStopStatus == ESTOP_ACTIVATED) {
526  if (firsttime) {
527  std::cout << "Emergency stop is activated! \n"
528  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
529  firsttime = false;
530  }
531  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
532  fflush(stdout);
533  CAL_Wait(1);
534  }
535  else {
536  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
537  std::cout << "You have to call Adept for maintenance..." << std::endl;
538  // Free allocated resources
539  ShutDownConnection();
540  exit(0);
541  }
542  }
543 
544  if (EStopStatus == ESTOP_ACTIVATED)
545  std::cout << std::endl;
546 
547  if (EStopStatus == ESTOP_ACTIVATED) {
548  std::cout << "Sorry, cannot power on the robot." << std::endl;
550  "Cannot power on the robot.");
551  }
552 
553  if (HIPowerStatus == 0) {
554  fprintf(stdout, "Power ON the Afma6 robot\n");
555  fflush(stdout);
556 
557  Try( PrimitivePOWERON_Afma6() );
558  }
559 
560  CatchPrint();
561  if (TryStt < 0) {
562  vpERROR_TRACE ("Cannot power on the robot");
564  "Cannot power off the robot.");
565  }
566 }
567 
577 void
579 {
580  InitTry;
581 
582  // Look if the power is on or off
583  UInt32 HIPowerStatus;
584  Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
585  &HIPowerStatus));
586  CAL_Wait(0.1);
587 
588  if (HIPowerStatus == 1) {
589  fprintf(stdout, "Power OFF the Afma6 robot\n");
590  fflush(stdout);
591 
592  Try( PrimitivePOWEROFF_Afma6() );
593  }
594 
595  CatchPrint();
596  if (TryStt < 0) {
597  vpERROR_TRACE ("Cannot power off the robot");
599  "Cannot power off the robot.");
600  }
601 }
602 
614 bool
616 {
617  InitTry;
618  bool status = false;
619  // Look if the power is on or off
620  UInt32 HIPowerStatus;
621  Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
622  &HIPowerStatus));
623  CAL_Wait(0.1);
624 
625  if (HIPowerStatus == 1) {
626  status = true;
627  }
628 
629  CatchPrint();
630  if (TryStt < 0) {
631  vpERROR_TRACE ("Cannot get the power status");
633  "Cannot get the power status.");
634  }
635  return status;
636 }
637 
647 void
649 {
650  vpHomogeneousMatrix cMe ;
651  vpAfma6::get_cMe(cMe) ;
652 
653  cVe.buildFrom(cMe) ;
654 }
655 
666 void
668 {
669  vpAfma6::get_cMe(cMe) ;
670 }
671 
672 
683 void
685 {
686 
687  double position[6];
688  double timestamp;
689 
690  InitTry;
691  Try( PrimitiveACQ_POS_Afma6(position, &timestamp) );
692  CatchPrint();
693 
694  vpColVector q(6);
695  for (unsigned int i=0; i < njoint; i++)
696  q[i] = position[i];
697 
698  try
699  {
700  vpAfma6::get_eJe(q, eJe) ;
701  }
702  catch(...)
703  {
704  vpERROR_TRACE("catch exception ") ;
705  throw ;
706  }
707 }
731  void
733 {
734 
735  double position[6];
736  double timestamp;
737 
738  InitTry;
739  Try( PrimitiveACQ_POS_Afma6(position, &timestamp) );
740  CatchPrint();
741 
742  vpColVector q(6);
743  for (unsigned int i=0; i < njoint; i++)
744  q[i] = position[i];
745 
746  try
747  {
748  vpAfma6::get_fJe(q, fJe) ;
749  }
750  catch(...)
751  {
752  vpERROR_TRACE("Error caught");
753  throw ;
754  }
755 }
756 
785 void
787 {
788  positioningVelocity = velocity;
789 }
790 
796 double
798 {
799  return positioningVelocity;
800 }
801 
876 void
878  const vpPoseVector & pose )
879 
880 {
881  vpColVector position(6);
882  vpRxyzVector rxyz;
884 
885  R.buildFrom(pose[3], pose[4], pose[5]); //thetau
886  rxyz.buildFrom(R);
887 
888  for (unsigned int i=0; i < 3; i++) {
889  position[i] = pose[i];
890  position[i+3] = rxyz[i];
891  }
892  if (frame == vpRobot::ARTICULAR_FRAME) {
894  "Positionning error: "
895  "Joint frame not implemented for pose positionning.");
896  }
897  setPosition (frame, position);
898 }
981 void
983  const vpColVector & position )
984 {
985 
987  {
988  vpERROR_TRACE ("Robot was not in position-based control\n"
989  "Modification of the robot state");
991  }
992 
993  double _destination[6];
994  int error = 0;
995  double timestamp;
996 
997  InitTry;
998  switch(frame) {
999  case vpRobot::CAMERA_FRAME : {
1000  double _q[njoint];
1001  Try( PrimitiveACQ_POS_Afma6(_q, &timestamp) );
1002 
1003  vpColVector q(njoint);
1004  for (unsigned int i=0; i < njoint; i++)
1005  q[i] = _q[i];
1006 
1007  // Get fMc from the inverse kinematics
1008  vpHomogeneousMatrix fMc;
1009  vpAfma6::get_fMc(q, fMc);
1010 
1011  // Set cMc from the input position
1012  vpTranslationVector txyz;
1013  vpRxyzVector rxyz;
1014  for (unsigned int i=0; i < 3; i++) {
1015  txyz[i] = position[i];
1016  rxyz[i] = position[i+3];
1017  }
1018 
1019  // Compute cMc2
1020  vpRotationMatrix cRc2(rxyz);
1021  vpHomogeneousMatrix cMc2(txyz, cRc2);
1022 
1023  // Compute the new position to reach: fMc*cMc2
1024  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1025 
1026  // Compute the corresponding joint position from the inverse kinematics
1027  bool nearest = true;
1028  int solution = this->getInverseKinematics(fMc2, q, nearest);
1029  if (solution) { // Position is reachable
1030  for (unsigned int i=0; i < njoint; i ++) {
1031  _destination[i] = q[i];
1032  }
1033  Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1034  Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1035  }
1036  else {
1037  // Cartesian position is out of range
1038  error = -1;
1039  }
1040 
1041  break ;
1042  }
1043  case vpRobot::ARTICULAR_FRAME: {
1044  for (unsigned int i=0; i < njoint; i ++) {
1045  _destination[i] = position[i];
1046  }
1047  Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1048  Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1049  break ;
1050 
1051  }
1052  case vpRobot::REFERENCE_FRAME: {
1053  // Set fMc from the input position
1054  vpTranslationVector txyz;
1055  vpRxyzVector rxyz;
1056  for (unsigned int i=0; i < 3; i++) {
1057  txyz[i] = position[i];
1058  rxyz[i] = position[i+3];
1059  }
1060  // Compute fMc from the input position
1061  vpRotationMatrix fRc(rxyz);
1062  vpHomogeneousMatrix fMc(txyz, fRc);
1063 
1064  // Compute the corresponding joint position from the inverse kinematics
1065  vpColVector q(6);
1066  bool nearest = true;
1067  int solution = this->getInverseKinematics(fMc, q, nearest);
1068  if (solution) { // Position is reachable
1069  for (unsigned int i=0; i < njoint; i ++) {
1070  _destination[i] = q[i];
1071  }
1072  Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1073  Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1074  }
1075  else {
1076  // Cartesian position is out of range
1077  error = -1;
1078  }
1079 
1080  break ;
1081  }
1082  case vpRobot::MIXT_FRAME:
1083  {
1084  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1086  "Positionning error: "
1087  "Mixt frame not implemented.");
1088  break ;
1089  }
1090  }
1091 
1092  CatchPrint();
1093  if (TryStt == InvalidPosition || TryStt == -1023)
1094  std::cout << " : Position out of range.\n";
1095  else if (TryStt < 0)
1096  std::cout << " : Unknown error (see Fabien).\n";
1097  else if (error == -1)
1098  std::cout << "Position out of range.\n";
1099 
1100  if (TryStt < 0 || error < 0) {
1101  vpERROR_TRACE ("Positionning error.");
1103  "Position out of range.");
1104  }
1105 
1106  return ;
1107 }
1108 
1177  const double pos1,
1178  const double pos2,
1179  const double pos3,
1180  const double pos4,
1181  const double pos5,
1182  const double pos6)
1183 {
1184  try{
1185  vpColVector position(6) ;
1186  position[0] = pos1 ;
1187  position[1] = pos2 ;
1188  position[2] = pos3 ;
1189  position[3] = pos4 ;
1190  position[4] = pos5 ;
1191  position[5] = pos6 ;
1192 
1193  setPosition(frame, position) ;
1194  }
1195  catch(...)
1196  {
1197  vpERROR_TRACE("Error caught");
1198  throw ;
1199  }
1200 }
1201 
1243 void vpRobotAfma6::setPosition(const char *filename)
1244 {
1245  vpColVector q;
1246  bool ret;
1247 
1248  ret = this->readPosFile(filename, q);
1249 
1250  if (ret == false) {
1251  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1253  "Bad position in filename.");
1254  }
1257 }
1258 
1312 void
1314  vpColVector & position, double &timestamp)
1315 {
1316 
1317  InitTry;
1318 
1319  position.resize (6);
1320 
1321  switch (frame) {
1322  case vpRobot::CAMERA_FRAME : {
1323  position = 0;
1324  return;
1325  }
1326  case vpRobot::ARTICULAR_FRAME : {
1327  double _q[njoint];
1328  Try( PrimitiveACQ_POS_Afma6(_q, &timestamp) );
1329  for (unsigned int i=0; i < njoint; i ++) {
1330  position[i] = _q[i];
1331  }
1332 
1333  return;
1334  }
1335  case vpRobot::REFERENCE_FRAME : {
1336  double _q[njoint];
1337  Try( PrimitiveACQ_POS_Afma6(_q, &timestamp) );
1338 
1339  vpColVector q(njoint);
1340  for (unsigned int i=0; i < njoint; i++)
1341  q[i] = _q[i];
1342 
1343  // Compute fMc
1344  vpHomogeneousMatrix fMc;
1345  vpAfma6::get_fMc(q, fMc);
1346 
1347  // From fMc extract the pose
1348  vpRotationMatrix fRc;
1349  fMc.extract(fRc);
1350  vpRxyzVector rxyz;
1351  rxyz.buildFrom(fRc);
1352 
1353  for (unsigned int i=0; i < 3; i++) {
1354  position[i] = fMc[i][3]; // translation x,y,z
1355  position[i+3] = rxyz[i]; // Euler rotation x,y,z
1356  }
1357  break ;
1358  }
1359  case vpRobot::MIXT_FRAME: {
1360  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1362  "Cannot get position in mixt frame: "
1363  "not implemented");
1364  break ;
1365  }
1366  }
1367 
1368  CatchPrint();
1369  if (TryStt < 0) {
1370  vpERROR_TRACE ("Cannot get position.");
1372  "Cannot get position.");
1373  }
1374 
1375  return;
1376 }
1381 {
1382  double timestamp;
1383  PrimitiveACQ_TIME_Afma6(&timestamp);
1384  return timestamp;
1385 }
1386 
1397  vpColVector &position)
1398 {
1399  double timestamp;
1400  getPosition(frame, position, timestamp);
1401 }
1402 
1411 void
1413  vpPoseVector &position, double &timestamp)
1414 {
1415  vpColVector posRxyz;
1416  //recupere position en Rxyz
1417  this->getPosition(frame, posRxyz, timestamp);
1418  vpRxyzVector RxyzVect;
1419  for(unsigned int j=0;j<3;j++)
1420  RxyzVect[j]=posRxyz[j+3];
1421  //recupere le vecteur thetaU correspondant
1422  vpThetaUVector RtuVect(RxyzVect);
1423 
1424  //remplit le vpPoseVector avec translation et rotation ThetaU
1425  for(unsigned int j=0;j<3;j++)
1426  {
1427  position[j]=posRxyz[j];
1428  position[j+3]=RtuVect[j];
1429  }
1430 }
1431 
1442  vpPoseVector &position)
1443 {
1444  double timestamp;
1445  getPosition(frame, position, timestamp);
1446 }
1447 
1502 void
1504  const vpColVector & vel)
1505 {
1507  {
1508  vpERROR_TRACE ("Cannot send a velocity to the robot "
1509  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1511  "Cannot send a velocity to the robot "
1512  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1513  }
1514 
1515  vpColVector vel_max(6);
1516 
1517  for (unsigned int i=0; i<3; i++)
1518  vel_max[i] = getMaxTranslationVelocity();
1519  for (unsigned int i=3; i<6; i++)
1520  vel_max[i] = getMaxRotationVelocity();
1521 
1522  vpColVector vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1523 
1524  InitTry;
1525 
1526  switch(frame) {
1527  case vpRobot::CAMERA_FRAME : {
1528  Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPCAM_AFMA6) );
1529  break ;
1530  }
1531  case vpRobot::ARTICULAR_FRAME : {
1532  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_AFMA6) );
1533  Try( PrimitiveMOVESPEED_Afma6(vel_sat.data) );
1534  break ;
1535  }
1536  case vpRobot::REFERENCE_FRAME : {
1537  Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPFIX_AFMA6) );
1538  break ;
1539  }
1540  case vpRobot::MIXT_FRAME : {
1541  Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPMIX_AFMA6) );
1542  break ;
1543  }
1544  default: {
1545  vpERROR_TRACE ("Error in spec of vpRobot. "
1546  "Case not taken in account.");
1547  return;
1548  }
1549  }
1550 
1551  Catch();
1552  if (TryStt < 0) {
1553  if (TryStt == VelStopOnJoint) {
1554  Int32 axisInJoint[njoint];
1555  PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1556  for (unsigned int i=0; i < njoint; i ++) {
1557  if (axisInJoint[i])
1558  std::cout << "\nWarning: Velocity control stopped: axis "
1559  << i+1 << " on joint limit!" <<std::endl;
1560  }
1561  }
1562  else {
1563  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1564  if (TryString != NULL) {
1565  // The statement is in TryString, but we need to check the validity
1566  printf(" Error sentence %s\n", TryString); // Print the TryString
1567  }
1568  else {
1569  printf("\n");
1570  }
1571  }
1572  }
1573 
1574  return;
1575 }
1576 
1577 
1578 
1579 
1580 
1581 
1582 /* ------------------------------------------------------------------------ */
1583 /* --- GET ---------------------------------------------------------------- */
1584 /* ------------------------------------------------------------------------ */
1585 
1586 
1636 void
1638  vpColVector & velocity, double &timestamp)
1639 {
1640  velocity.resize (6);
1641  velocity = 0;
1642 
1643  double q[6];
1644  vpColVector q_cur(6);
1645  vpHomogeneousMatrix fMc_cur;
1646  vpHomogeneousMatrix cMc; // camera displacement
1647  double time_cur;
1648 
1649  InitTry;
1650 
1651  // Get the current joint position
1652  Try( PrimitiveACQ_POS_Afma6(q, &timestamp) );
1653  time_cur = timestamp;
1654  for (unsigned int i=0; i < njoint; i ++) {
1655  q_cur[i] = q[i];
1656  }
1657 
1658  // Get the camera pose from the direct kinematics
1659  vpAfma6::get_fMc(q_cur, fMc_cur);
1660 
1661  if ( ! first_time_getvel ) {
1662 
1663  switch (frame) {
1664  case vpRobot::CAMERA_FRAME: {
1665  // Compute the displacement of the camera since the previous call
1666  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1667 
1668  // Compute the velocity of the camera from this displacement
1669  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1670 
1671  break ;
1672  }
1673 
1674  case vpRobot::ARTICULAR_FRAME: {
1675  velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1676  break ;
1677  }
1678 
1679  case vpRobot::REFERENCE_FRAME: {
1680  // Compute the displacement of the camera since the previous call
1681  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1682 
1683  // Compute the velocity of the camera from this displacement
1684  vpColVector v;
1685  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1686 
1687  // Express this velocity in the reference frame
1688  vpVelocityTwistMatrix fVc(fMc_cur);
1689  velocity = fVc * v;
1690 
1691  break ;
1692  }
1693 
1694  case vpRobot::MIXT_FRAME: {
1695  // Compute the displacement of the camera since the previous call
1696  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1697 
1698  // Compute the ThetaU representation for the rotation
1699  vpRotationMatrix cRc;
1700  cMc.extract(cRc);
1701  vpThetaUVector thetaU;
1702  thetaU.buildFrom(cRc);
1703 
1704  for (unsigned int i=0; i < 3; i++) {
1705  // Compute the translation displacement in the reference frame
1706  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1707  // Update the rotation displacement in the camera frame
1708  velocity[i+3] = thetaU[i];
1709  }
1710 
1711  // Compute the velocity
1712  velocity /= (time_cur - time_prev_getvel);
1713  break ;
1714  }
1715  }
1716  }
1717  else {
1718  first_time_getvel = false;
1719  }
1720 
1721  // Memorize the camera pose for the next call
1722  fMc_prev_getvel = fMc_cur;
1723 
1724  // Memorize the joint position for the next call
1725  q_prev_getvel = q_cur;
1726 
1727  // Memorize the time associated to the joint position for the next call
1728  time_prev_getvel = time_cur;
1729 
1730 
1731  CatchPrint();
1732  if (TryStt < 0) {
1733  vpERROR_TRACE ("Cannot get velocity.");
1735  "Cannot get velocity.");
1736  }
1737 }
1738 
1748  vpColVector & velocity)
1749 {
1750  double timestamp;
1751  getVelocity(frame, velocity, timestamp);
1752 }
1753 
1754 
1798 {
1799  vpColVector velocity;
1800  getVelocity (frame, velocity, timestamp);
1801 
1802  return velocity;
1803 }
1804 
1814 {
1815  vpColVector velocity;
1816  double timestamp;
1817  getVelocity (frame, velocity, timestamp);
1818 
1819  return velocity;
1820 }
1821 
1870 bool
1871 vpRobotAfma6::readPosFile(const char *filename, vpColVector &q)
1872 {
1873 
1874  FILE * fd ;
1875  fd = fopen(filename, "r") ;
1876  if (fd == NULL)
1877  return false;
1878 
1879  char line[FILENAME_MAX];
1880  char dummy[FILENAME_MAX];
1881  char head[] = "R:";
1882  bool sortie = false;
1883 
1884  do {
1885  // Saut des lignes commencant par #
1886  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1887  if ( strncmp (line, "#", 1) != 0) {
1888  // La ligne n'est pas un commentaire
1889  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1890  sortie = true; // Position robot trouvee.
1891  }
1892 // else
1893 // return (false); // fin fichier sans position robot.
1894  }
1895  }
1896  else {
1897  return (false); /* fin fichier */
1898  }
1899 
1900  }
1901  while ( sortie != true );
1902 
1903  // Lecture des positions
1904  q.resize(njoint);
1905  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1906  dummy,
1907  &q[0], &q[1], &q[2],
1908  &q[3], &q[4], &q[5]);
1909 
1910  // converts rotations from degrees into radians
1911  for (unsigned int i=3; i < njoint; i ++)
1912  q[i] = vpMath::rad(q[i]) ;
1913 
1914  fclose(fd) ;
1915  return (true);
1916 }
1917 
1942 bool
1943 vpRobotAfma6::savePosFile(const char *filename, const vpColVector &q)
1944 {
1945 
1946  FILE * fd ;
1947  fd = fopen(filename, "w") ;
1948  if (fd == NULL)
1949  return false;
1950 
1951  fprintf(fd, "\
1952 #AFMA6 - Position - Version 2.01\n\
1953 #\n\
1954 # R: X Y Z A B C\n\
1955 # Joint position: X, Y, Z: translations in meters\n\
1956 # A, B, C: rotations in degrees\n\
1957 #\n\
1958 #\n\n");
1959 
1960  // Save positions in mm and deg
1961  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
1962  q[0],
1963  q[1],
1964  q[2],
1965  vpMath::deg(q[3]),
1966  vpMath::deg(q[4]),
1967  vpMath::deg(q[5]));
1968 
1969  fclose(fd) ;
1970  return (true);
1971 }
1972 
1983 void
1984 vpRobotAfma6::move(const char *filename)
1985 {
1986  vpColVector q;
1987 
1988  this->readPosFile(filename, q) ;
1990  this->setPositioningVelocity(10);
1992 }
1993 
2006 void
2007 vpRobotAfma6::move(const char *filename, const double velocity)
2008 {
2009  vpColVector q;
2010 
2011  this->readPosFile(filename, q) ;
2013  this->setPositioningVelocity(velocity);
2015 }
2016 
2023 void
2025 {
2026  InitTry;
2027  Try( PrimitiveGripper_Afma6(1) );
2028  std::cout << "Open the gripper..." << std::endl;
2029  CatchPrint();
2030  if (TryStt < 0) {
2031  vpERROR_TRACE ("Cannot open the gripper");
2033  "Cannot open the gripper.");
2034  }
2035 }
2036 
2044 void
2046 {
2047  InitTry;
2048  Try( PrimitiveGripper_Afma6(0) );
2049  std::cout << "Close the gripper..." << std::endl;
2050  CatchPrint();
2051  if (TryStt < 0) {
2052  vpERROR_TRACE ("Cannot close the gripper");
2054  "Cannot close the gripper.");
2055  }
2056 }
2057 
2071 void
2072 vpRobotAfma6::getCameraDisplacement(vpColVector &displacement)
2073 {
2074  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2075 }
2087 void
2088 vpRobotAfma6::getArticularDisplacement(vpColVector &displacement)
2089 {
2091 }
2092 
2113 void
2115  vpColVector &displacement)
2116 {
2117  displacement.resize (6);
2118  displacement = 0;
2119 
2120  double q[6];
2121  vpColVector q_cur(6);
2122  vpHomogeneousMatrix fMc_cur, c_prevMc_cur;
2123  double timestamp;
2124 
2125  InitTry;
2126 
2127  // Get the current joint position
2128  Try( PrimitiveACQ_POS_Afma6(q, &timestamp) );
2129  for (unsigned int i=0; i < njoint; i ++) {
2130  q_cur[i] = q[i];
2131  }
2132 
2133  // Compute the camera pose in the reference frame
2134  fMc_cur = get_fMc(q_cur);
2135 
2136  if ( ! first_time_getdis ) {
2137  switch (frame) {
2138  case vpRobot::CAMERA_FRAME: {
2139  // Compute the camera dispacement from the previous pose
2140  c_prevMc_cur = fMc_prev_getdis.inverse() * fMc_cur;
2141 
2143  vpRotationMatrix R;
2144  c_prevMc_cur.extract(t);
2145  c_prevMc_cur.extract(R);
2146 
2147  vpRxyzVector rxyz;
2148  rxyz.buildFrom(R);
2149 
2150  for (unsigned int i=0; i<3; i++) {
2151  displacement[i] = t[i];
2152  displacement[i+3] = rxyz[i];
2153  }
2154  break ;
2155  }
2156 
2157  case vpRobot::ARTICULAR_FRAME: {
2158  displacement = q_cur - q_prev_getdis;
2159  break ;
2160  }
2161 
2162  case vpRobot::REFERENCE_FRAME: {
2163  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2164  return;
2165  break ;
2166  }
2167 
2168  case vpRobot::MIXT_FRAME: {
2169  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2170  return;
2171  break ;
2172  }
2173  }
2174  }
2175  else {
2176  first_time_getdis = false;
2177  }
2178 
2179  // Memorize the joint position for the next call
2180  q_prev_getdis = q_cur;
2181 
2182  // Memorize the pose for the next call
2183  fMc_prev_getdis = fMc_cur;
2184 
2185  CatchPrint();
2186  if (TryStt < 0) {
2187  vpERROR_TRACE ("Cannot get velocity.");
2189  "Cannot get velocity.");
2190  }
2191 }
2192 
2203 bool
2205 {
2206  Int32 axisInJoint[njoint];
2207  bool status = true;
2208  jointsStatus.resize(6);
2209  InitTry;
2210 
2211  Try (PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint,
2212 NULL));
2213  for (unsigned int i=0; i < njoint; i ++) {
2214  if (axisInJoint[i]){
2215  std::cout << "\nWarning: Velocity control stopped: axis "
2216  << i+1 << " on joint limit!" <<std::endl;
2217  jointsStatus[i] = axisInJoint[i];
2218  status = false;
2219  }
2220  else{
2221  jointsStatus[i] = 0;
2222  }
2223  }
2224 
2225  Catch();
2226  if (TryStt < 0) {
2227  vpERROR_TRACE ("Cannot check joint limits.");
2229  "Cannot check joint limits.");
2230  }
2231 
2232  return status;
2233 
2234 }
2235 
2236 #elif !defined(VISP_BUILD_SHARED_LIBS)
2237 // Work arround to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no symbols
2238 void dummy_vpRobotAfma6() {};
2239 #endif
2240 
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Modelisation of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:65
static vpColVector inverse(const vpHomogeneousMatrix &M)
bool getPowerState()
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
vpRxyzVector buildFrom(const vpRotationMatrix &R)
vpRxyzVector _erc
Definition: vpAfma6.h:186
bool checkJointLimits(vpColVector &jointsStatus)
vpTranslationVector _etc
Definition: vpAfma6.h:185
static const unsigned int njoint
Number of joint.
Definition: vpAfma6.h:172
void get_eJe(vpMatrix &_eJe)
Error that can be emited by the vpRobot class and its derivates.
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition: vpAfma6.cpp:560
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
Definition: vpRobot.h:156
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:741
static bool savePosFile(const char *filename, const vpColVector &q)
#define vpERROR_TRACE
Definition: vpDebug.h:391
double _coupl_56
Definition: vpAfma6.h:180
void setPosition(const vpRobot::vpControlFrameType frame, const vpPoseVector &pose)
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
Initialize the position controller.
Definition: vpRobot.h:69
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpAfma6.cpp:895
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:104
class that defines a generic virtual robot
Definition: vpRobot.h:58
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:84
vpControlFrameType
Definition: vpRobot.h:76
double getPositioningVelocity(void)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual ~vpRobotAfma6(void)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setPositioningVelocity(const double velocity)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition: vpAfma6.h:170
Implementation of a rotation matrix and operations on such kind of matrices.
void init(void)
void get_cMe(vpHomogeneousMatrix &_cMe) const
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpAfma6.h:113
Initialize the velocity controller.
Definition: vpRobot.h:68
vpRobotStateType
Definition: vpRobot.h:64
bool verbose_
Definition: vpRobot.h:113
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M)
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:857
void get_fJe(vpMatrix &_fJe)
void extract(vpRotationMatrix &R) const
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Implementation of a velocity twist matrix and operations on such kind of matrices.
static double rad(double deg)
Definition: vpMath.h:104
double _long_56
Definition: vpAfma6.h:181
void move(const char *filename)
static double deg(double rad)
Definition: vpMath.h:97
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:138
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
void init(void)
Definition: vpAfma6.cpp:195
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
double _joint_max[6]
Definition: vpAfma6.h:182
static bool readPosFile(const char *filename, vpColVector &q)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:964
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
double _joint_min[6]
Definition: vpAfma6.h:183
static const double defaultPositioningVelocity
Definition: vpRobotAfma6.h:258
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
double getTime() const
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:217
void get_cVe(vpVelocityTwistMatrix &_cVe) const