ViSP  2.7.0
vpRobotViper650.cpp
1 /****************************************************************************
2  *
3  * $Id: vpRobotViper650.cpp 4107 2013-02-06 10:04:49Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2013 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Interface for the Irisa's Viper S650 robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
42 #include <visp/vpConfig.h>
43 
44 #ifdef VISP_HAVE_VIPER650
45 
46 #include <signal.h>
47 #include <stdlib.h>
48 #include <sys/types.h>
49 #include <unistd.h>
50 
51 #include <visp/vpRobotException.h>
52 #include <visp/vpExponentialMap.h>
53 #include <visp/vpDebug.h>
54 #include <visp/vpVelocityTwistMatrix.h>
55 #include <visp/vpThetaUVector.h>
56 #include <visp/vpRobot.h>
57 #include <visp/vpRobotViper650.h>
58 
59 /* ---------------------------------------------------------------------- */
60 /* --- STATIC ----------------------------------------------------------- */
61 /* ---------------------------------------------------------------------- */
62 
63 bool vpRobotViper650::robotAlreadyCreated = false;
64 
73 
74 /* ---------------------------------------------------------------------- */
75 /* --- EMERGENCY STOP --------------------------------------------------- */
76 /* ---------------------------------------------------------------------- */
77 
85 void emergencyStopViper650(int signo)
86 {
87  std::cout << "Stop the Viper650 application by signal ("
88  << signo << "): " << (char)7 ;
89  switch(signo)
90  {
91  case SIGINT:
92  std::cout << "SIGINT (stop by ^C) " << std::endl ; break ;
93  case SIGBUS:
94  std::cout <<"SIGBUS (stop due to a bus error) " << std::endl ; break ;
95  case SIGSEGV:
96  std::cout <<"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
97  case SIGKILL:
98  std::cout <<"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
99  case SIGQUIT:
100  std::cout <<"SIGQUIT " << std::endl ; break ;
101  default :
102  std::cout << signo << std::endl ;
103 }
104  //std::cout << "Emergency stop called\n";
105  // PrimitiveESTOP_Viper650();
106  PrimitiveSTOP_Viper650();
107  std::cout << "Robot was stopped\n";
108 
109  // Free allocated resources
110  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
111 
112  fprintf(stdout, "Application ");
113  fflush(stdout);
114  kill(getpid(), SIGKILL);
115  exit(1) ;
116 }
117 
118 /* ---------------------------------------------------------------------- */
119 /* --- CONSTRUCTOR ------------------------------------------------------ */
120 /* ---------------------------------------------------------------------- */
121 
177 vpRobotViper650::vpRobotViper650 (bool verbose)
178  :
179  vpViper650 (),
180  vpRobot ()
181 {
182 
183  /*
184  #define SIGHUP 1 // hangup
185  #define SIGINT 2 // interrupt (rubout)
186  #define SIGQUIT 3 // quit (ASCII FS)
187  #define SIGILL 4 // illegal instruction (not reset when caught)
188  #define SIGTRAP 5 // trace trap (not reset when caught)
189  #define SIGIOT 6 // IOT instruction
190  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
191  #define SIGEMT 7 // EMT instruction
192  #define SIGFPE 8 // floating point exception
193  #define SIGKILL 9 // kill (cannot be caught or ignored)
194  #define SIGBUS 10 // bus error
195  #define SIGSEGV 11 // segmentation violation
196  #define SIGSYS 12 // bad argument to system call
197  #define SIGPIPE 13 // write on a pipe with no one to read it
198  #define SIGALRM 14 // alarm clock
199  #define SIGTERM 15 // software termination signal from kill
200  */
201 
202  signal(SIGINT, emergencyStopViper650);
203  signal(SIGBUS, emergencyStopViper650) ;
204  signal(SIGSEGV, emergencyStopViper650) ;
205  signal(SIGKILL, emergencyStopViper650);
206  signal(SIGQUIT, emergencyStopViper650);
207 
208  setVerbose(verbose);
209  if (verbose_)
210  std::cout << "Open communication with MotionBlox.\n";
211  try {
212  this->init();
214  }
215  catch(...) {
216  // vpERROR_TRACE("Error caught") ;
217  throw ;
218  }
219  positioningVelocity = defaultPositioningVelocity ;
220 
221  vpRobotViper650::robotAlreadyCreated = true;
222 
223  return ;
224 }
225 
226 
227 /* ------------------------------------------------------------------------ */
228 /* --- INITIALISATION ----------------------------------------------------- */
229 /* ------------------------------------------------------------------------ */
230 
250 void
252 {
253  InitTry;
254 
255  // Initialise private variables used to compute the measured velocities
256  q_prev_getvel.resize(6);
257  q_prev_getvel = 0;
258  time_prev_getvel = 0;
259  first_time_getvel = true;
260 
261  // Initialise private variables used to compute the measured displacement
262  q_prev_getdis.resize(6);
263  q_prev_getdis = 0;
264  first_time_getdis = true;
265 
266  // Initialize the firewire connection
267  Try( InitializeConnection(verbose_) );
268 
269  // Connect to the servoboard using the servo board GUID
270  Try( InitializeNode_Viper650() );
271 
272  Try( PrimitiveRESET_Viper650() );
273 
274  // Update the eMc matrix in the low level controller
276 
277  // Look if the power is on or off
278  UInt32 HIPowerStatus;
279  UInt32 EStopStatus;
280  Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
281  &HIPowerStatus));
282  CAL_Wait(0.1);
283 
284  // Print the robot status
285  if (verbose_) {
286  std::cout << "Robot status: ";
287  switch(EStopStatus) {
288  case ESTOP_AUTO:
289  controlMode = AUTO;
290  if (HIPowerStatus == 0)
291  std::cout << "Power is OFF" << std::endl;
292  else
293  std::cout << "Power is ON" << std::endl;
294  break;
295 
296  case ESTOP_MANUAL:
297  controlMode = MANUAL;
298  if (HIPowerStatus == 0)
299  std::cout << "Power is OFF" << std::endl;
300  else
301  std::cout << "Power is ON" << std::endl;
302  break;
303  case ESTOP_ACTIVATED:
304  controlMode = ESTOP;
305  std::cout << "Emergency stop is activated" << std::endl;
306  break;
307  default:
308  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
309  std::cout << "You have to call Adept for maintenance..." << std::endl;
310  // Free allocated resources
311  }
312  std::cout << std::endl;
313  }
314  // get real joint min/max from the MotionBlox
315  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
316  // Convert units from degrees to radians
317  joint_min.deg2rad();
318  joint_max.deg2rad();
319 
320  // for (unsigned int i=0; i < njoint; i++) {
321  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
322  // }
323 
324  // If an error occur in the low level controller, goto here
325  //CatchPrint();
326  Catch();
327 
328  // Test if an error occurs
329  if (TryStt == -20001)
330  printf("No connection detected. Check if the robot is powered on \n"
331  "and if the firewire link exist between the MotionBlox and this computer.\n");
332  else if (TryStt == -675)
333  printf(" Timeout enabling power...\n");
334 
335  if (TryStt < 0) {
336  // Power off the robot
337  PrimitivePOWEROFF_Viper650();
338  // Free allocated resources
339  ShutDownConnection();
340 
341  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
343  "Cannot open connexion with the motionblox");
344  }
345  return ;
346 }
347 
404 void
407 {
408 
409  InitTry;
410  // Read the robot constants from files
411  // - joint [min,max], coupl_56, long_56
412  // - camera extrinsic parameters relative to eMc
413  vpViper650::init(tool, projModel);
414 
415  // Set the camera constant (eMc pose) in the MotionBlox
416  double eMc_pose[6];
417  for (unsigned int i=0; i < 3; i ++) {
418  eMc_pose[i] = etc[i]; // translation in meters
419  eMc_pose[i+3] = erc[i]; // rotation in rad
420  }
421  // Update the eMc pose in the low level controller
422  Try( PrimitiveCONST_Viper650(eMc_pose) );
423 
424  // get real joint min/max from the MotionBlox
425  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
426  // Convert units from degrees to radians
427  joint_min.deg2rad();
428  joint_max.deg2rad();
429 
430  // for (unsigned int i=0; i < njoint; i++) {
431  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
432  // }
433 
434  setToolType(tool);
435 
436  CatchPrint();
437  return ;
438 }
439 
440 /* ------------------------------------------------------------------------ */
441 /* --- DESTRUCTOR --------------------------------------------------------- */
442 /* ------------------------------------------------------------------------ */
443 
451 {
452  InitTry;
453 
455 
456  // Look if the power is on or off
457  UInt32 HIPowerStatus;
458  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
459  &HIPowerStatus));
460  CAL_Wait(0.1);
461 
462  // if (HIPowerStatus == 1) {
463  // fprintf(stdout, "Power OFF the robot\n");
464  // fflush(stdout);
465 
466  // Try( PrimitivePOWEROFF_Viper650() );
467  // }
468 
469  // Free allocated resources
470  ShutDownConnection();
471 
472  vpRobotViper650::robotAlreadyCreated = false;
473 
474  CatchPrint();
475  return;
476 }
477 
478 
479 
480 
489 {
490  InitTry;
491 
492  switch (newState) {
493  case vpRobot::STATE_STOP: {
494  // Start primitive STOP only if the current state is Velocity
496  Try( PrimitiveSTOP_Viper650() );
497  }
498  break;
499  }
502  std::cout << "Change the control mode from velocity to position control.\n";
503  Try( PrimitiveSTOP_Viper650() );
504  }
505  else {
506  //std::cout << "Change the control mode from stop to position control.\n";
507  }
508  this->powerOn();
509  break;
510  }
513  std::cout << "Change the control mode from stop to velocity control.\n";
514  }
515  this->powerOn();
516  break;
517  }
518  default:
519  break ;
520  }
521 
522  CatchPrint();
523 
524  return vpRobot::setRobotState (newState);
525 }
526 
527 
528 /* ------------------------------------------------------------------------ */
529 /* --- STOP --------------------------------------------------------------- */
530 /* ------------------------------------------------------------------------ */
531 
539 void
541 {
543  return;
544 
545  InitTry;
546  Try( PrimitiveSTOP_Viper650() );
548 
549  CatchPrint();
550  if (TryStt < 0) {
551  vpERROR_TRACE ("Cannot stop robot motion");
553  "Cannot stop robot motion.");
554  }
555 }
556 
566 void
568 {
569  InitTry;
570 
571  // Look if the power is on or off
572  UInt32 HIPowerStatus;
573  UInt32 EStopStatus;
574  bool firsttime = true;
575  unsigned int nitermax = 10;
576 
577  for (unsigned int i=0; i<nitermax; i++) {
578  Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
579  &HIPowerStatus));
580  if (EStopStatus == ESTOP_AUTO) {
581  controlMode = AUTO;
582  break; // exit for loop
583  }
584  else if (EStopStatus == ESTOP_MANUAL) {
585  controlMode = MANUAL;
586  break; // exit for loop
587  }
588  else if (EStopStatus == ESTOP_ACTIVATED) {
589  controlMode = ESTOP;
590  if (firsttime) {
591  std::cout << "Emergency stop is activated! \n"
592  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
593  firsttime = false;
594  }
595  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
596  fflush(stdout);
597  CAL_Wait(1);
598  }
599  else {
600  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
601  std::cout << "You have to call Adept for maintenance..." << std::endl;
602  // Free allocated resources
603  ShutDownConnection();
604  exit(0);
605  }
606  }
607 
608  if (EStopStatus == ESTOP_ACTIVATED)
609  std::cout << std::endl;
610 
611  if (EStopStatus == ESTOP_ACTIVATED) {
612  std::cout << "Sorry, cannot power on the robot." << std::endl;
614  "Cannot power on the robot.");
615  }
616 
617  if (HIPowerStatus == 0) {
618  fprintf(stdout, "Power ON the Viper650 robot\n");
619  fflush(stdout);
620 
621  Try( PrimitivePOWERON_Viper650() );
622  }
623 
624  CatchPrint();
625  if (TryStt < 0) {
626  vpERROR_TRACE ("Cannot power on the robot");
628  "Cannot power off the robot.");
629  }
630 }
631 
641 void
643 {
644  InitTry;
645 
646  // Look if the power is on or off
647  UInt32 HIPowerStatus;
648  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
649  &HIPowerStatus));
650  CAL_Wait(0.1);
651 
652  if (HIPowerStatus == 1) {
653  fprintf(stdout, "Power OFF the Viper650 robot\n");
654  fflush(stdout);
655 
656  Try( PrimitivePOWEROFF_Viper650() );
657  }
658 
659  CatchPrint();
660  if (TryStt < 0) {
661  vpERROR_TRACE ("Cannot power off the robot");
663  "Cannot power off the robot.");
664  }
665 }
666 
678 bool
680 {
681  InitTry;
682  bool status = false;
683  // Look if the power is on or off
684  UInt32 HIPowerStatus;
685  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
686  &HIPowerStatus));
687  CAL_Wait(0.1);
688 
689  if (HIPowerStatus == 1) {
690  status = true;
691  }
692 
693  CatchPrint();
694  if (TryStt < 0) {
695  vpERROR_TRACE ("Cannot get the power status");
697  "Cannot get the power status.");
698  }
699  return status;
700 }
701 
711 void
713 {
714  vpHomogeneousMatrix cMe ;
715  vpViper650::get_cMe(cMe) ;
716 
717  cVe.buildFrom(cMe) ;
718 }
719 
731 void
733 {
734  vpViper650::get_cMe(cMe) ;
735 }
736 
737 
749 void
751 {
752 
753  double position[6];
754  double timestamp;
755 
756  InitTry;
757  Try( PrimitiveACQ_POS_J_Viper650(position, &timestamp) );
758  CatchPrint();
759 
760  vpColVector q(6);
761  for (unsigned int i=0; i < njoint; i++)
762  q[i] = vpMath::rad(position[i]);
763 
764  try
765  {
766  vpViper650::get_eJe(q, eJe) ;
767  }
768  catch(...)
769  {
770  vpERROR_TRACE("catch exception ") ;
771  throw ;
772  }
773 }
786 void
788 {
789 
790  double position[6];
791  double timestamp;
792 
793  InitTry;
794  Try( PrimitiveACQ_POS_Viper650(position, &timestamp) );
795  CatchPrint();
796 
797  vpColVector q(6);
798  for (unsigned int i=0; i < njoint; i++)
799  q[i] = position[i];
800 
801  try
802  {
803  vpViper650::get_fJe(q, fJe) ;
804  }
805  catch(...)
806  {
807  vpERROR_TRACE("Error caught");
808  throw ;
809  }
810 }
811 
849 void
851 {
852  positioningVelocity = velocity;
853 }
854 
860 double
862 {
863  return positioningVelocity;
864 }
865 
866 
944 void
946  const vpColVector & position )
947 {
948 
950  {
951  vpERROR_TRACE ("Robot was not in position-based control\n"
952  "Modification of the robot state");
954  }
955 
956  vpColVector destination(njoint);
957  int error = 0;
958  double timestamp;
959 
960  InitTry;
961  switch(frame) {
962  case vpRobot::CAMERA_FRAME : {
963  vpColVector q(njoint);
964  Try( PrimitiveACQ_POS_Viper650(q.data, &timestamp) );
965 
966  // Convert degrees into rad
967  q.deg2rad();
968 
969  // Get fMc from the inverse kinematics
971  vpViper650::get_fMc(q, fMc);
972 
973  // Set cMc from the input position
974  vpTranslationVector txyz;
975  vpRxyzVector rxyz;
976  for (unsigned int i=0; i < 3; i++) {
977  txyz[i] = position[i];
978  rxyz[i] = position[i+3];
979  }
980 
981  // Compute cMc2
982  vpRotationMatrix cRc2(rxyz);
983  vpHomogeneousMatrix cMc2(txyz, cRc2);
984 
985  // Compute the new position to reach: fMc*cMc2
986  vpHomogeneousMatrix fMc2 = fMc * cMc2;
987 
988  // Compute the corresponding joint position from the inverse kinematics
989  unsigned int solution = this->getInverseKinematics(fMc2, q);
990  if (solution) { // Position is reachable
991  destination = q;
992  // convert rad to deg requested for the low level controller
993  destination.rad2deg();
994  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
995  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
996  }
997  else {
998  // Cartesian position is out of range
999  error = -1;
1000  }
1001 
1002  break ;
1003  }
1004  case vpRobot::ARTICULAR_FRAME: {
1005  destination = position;
1006  // convert rad to deg requested for the low level controller
1007  destination.rad2deg();
1008 
1009  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1010  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
1011  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1012  break ;
1013 
1014  }
1015  case vpRobot::REFERENCE_FRAME: {
1016  // Convert angles from Rxyz representation to Rzyz representation
1017  vpRxyzVector rxyz(position[3],position[4],position[5]);
1018  vpRotationMatrix R(rxyz);
1019  vpRzyzVector rzyz(R);
1020 
1021  for (unsigned int i=0; i <3; i++) {
1022  destination[i] = position[i];
1023  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1024  }
1025  int configuration = 0; // keep the actual configuration
1026 
1027  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1028  Try( PrimitiveMOVE_C_Viper650(destination.data, configuration,
1029  positioningVelocity) );
1030  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1031 
1032  break ;
1033  }
1034  case vpRobot::MIXT_FRAME:
1035  {
1036  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1038  "Positionning error: "
1039  "Mixt frame not implemented.");
1040  break ;
1041  }
1042  }
1043 
1044  CatchPrint();
1045  if (TryStt == InvalidPosition || TryStt == -1023)
1046  std::cout << " : Position out of range.\n";
1047 
1048  else if (TryStt == -3019) {
1049  if (frame == vpRobot::ARTICULAR_FRAME)
1050  std::cout << " : Joint position out of range.\n";
1051  else
1052  std::cout << " : Cartesian position leads to a joint position out of range.\n";
1053  }
1054  else if (TryStt < 0)
1055  std::cout << " : Unknown error (see Fabien).\n";
1056  else if (error == -1)
1057  std::cout << "Position out of range.\n";
1058 
1059  if (TryStt < 0 || error < 0) {
1060  vpERROR_TRACE ("Positionning error.");
1062  "Position out of range.");
1063  }
1064 
1065  return ;
1066 }
1067 
1134  const double pos1,
1135  const double pos2,
1136  const double pos3,
1137  const double pos4,
1138  const double pos5,
1139  const double pos6)
1140 {
1141  try{
1142  vpColVector position(6) ;
1143  position[0] = pos1 ;
1144  position[1] = pos2 ;
1145  position[2] = pos3 ;
1146  position[3] = pos4 ;
1147  position[4] = pos5 ;
1148  position[5] = pos6 ;
1149 
1150  setPosition(frame, position) ;
1151  }
1152  catch(...)
1153  {
1154  vpERROR_TRACE("Error caught");
1155  throw ;
1156  }
1157 }
1158 
1198 void vpRobotViper650::setPosition(const char *filename)
1199 {
1200  vpColVector q;
1201  bool ret;
1202 
1203  ret = this->readPosFile(filename, q);
1204 
1205  if (ret == false) {
1206  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1208  "Bad position in filename.");
1209  }
1212 }
1213 
1283  vpColVector &position,
1284  double &timestamp)
1285 {
1286 
1287  InitTry;
1288 
1289  position.resize (6);
1290 
1291  switch (frame) {
1292  case vpRobot::CAMERA_FRAME : {
1293  position = 0;
1294  return;
1295  }
1296  case vpRobot::ARTICULAR_FRAME : {
1297  Try( PrimitiveACQ_POS_J_Viper650(position.data, &timestamp) );
1298  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1299  position.deg2rad();
1300 
1301  return;
1302  }
1303  case vpRobot::REFERENCE_FRAME : {
1304  Try( PrimitiveACQ_POS_C_Viper650(position.data, &timestamp) );
1305  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1306  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1307  // Convert Euler Rzyz angles from deg to rad
1308  for (unsigned int i=3; i <6; i++)
1309  position[i] = vpMath::rad(position[i]);
1310  // Convert Rzyz angles into Rxyz representation
1311  vpRzyzVector rzyz(position[3], position[4], position[5]);
1312  vpRotationMatrix R(rzyz);
1313  vpRxyzVector rxyz(R);
1314 
1315  // Update the position using Rxyz representation
1316  for (unsigned int i=0; i <3; i++)
1317  position[i+3] = rxyz[i];
1318  // vpCTRACE << "Cartesian position Rxyz (deg)"
1319  // << position[0] << " " << position[1] << " " << position[2] << " "
1320  // << vpMath::deg(position[3]) << " "
1321  // << vpMath::deg(position[4]) << " "
1322  // << vpMath::deg(position[5]) << std::endl;
1323 
1324  break ;
1325  }
1326  case vpRobot::MIXT_FRAME: {
1327  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1329  "Cannot get position in mixt frame: "
1330  "not implemented");
1331  break ;
1332  }
1333  }
1334 
1335  CatchPrint();
1336  if (TryStt < 0) {
1337  vpERROR_TRACE ("Cannot get position.");
1339  "Cannot get position.");
1340  }
1341 
1342  return;
1343 }
1344 
1355  vpColVector &position)
1356 {
1357  double timestamp;
1358  getPosition(frame, position, timestamp);
1359 }
1360 
1373  vpPoseVector &position,
1374  double &timestamp)
1375 {
1376  vpColVector posRxyz;
1377  //recupere position en Rxyz
1378  this->getPosition(frame, posRxyz, timestamp);
1379  vpRxyzVector RxyzVect;
1380  for (unsigned int j=0;j<3;j++)
1381  RxyzVect[j]=posRxyz[j+3];
1382  //recupere le vecteur thetaU correspondant
1383  vpThetaUVector RtuVect(RxyzVect);
1384 
1385  //remplit le vpPoseVector avec translation et rotation ThetaU
1386  for (unsigned int j=0;j<3;j++)
1387  {
1388  position[j]=posRxyz[j];
1389  position[j+3]=RtuVect[j];
1390  }
1391 }
1392 
1403  vpPoseVector &position)
1404 {
1405  double timestamp;
1406  getPosition(frame, position, timestamp);
1407 }
1408 
1413 {
1414  double timestamp;
1415  PrimitiveACQ_TIME_Viper650(&timestamp);
1416  return timestamp;
1417 }
1418 
1491 void
1493  const vpColVector & vel)
1494 {
1496  vpERROR_TRACE ("Cannot send a velocity to the robot "
1497  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1499  "Cannot send a velocity to the robot "
1500  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1501  }
1502 
1503  vpColVector vel_sat(6);
1504 
1505  // Velocity saturation
1506  switch(frame) {
1507  // saturation in cartesian space
1508  case vpRobot::CAMERA_FRAME :
1510  case vpRobot::MIXT_FRAME : {
1511  vpColVector vel_max(6);
1512 
1513  for (unsigned int i=0; i<3; i++)
1514  vel_max[i] = getMaxTranslationVelocity();
1515  for (unsigned int i=3; i<6; i++)
1516  vel_max[i] = getMaxRotationVelocity();
1517 
1518  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1519 
1520  break;
1521  }
1522  // saturation in joint space
1523  case vpRobot::ARTICULAR_FRAME : {
1524  vpColVector vel_max(6);
1525 
1526  for (unsigned int i=0; i<6; i++)
1527  vel_max[i] = getMaxRotationVelocity();
1528 
1529  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1530  }
1531  }
1532 
1533  InitTry;
1534 
1535  switch(frame) {
1536  case vpRobot::CAMERA_FRAME : {
1537  // Send velocities in m/s and rad/s
1538  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1539  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPCAM_VIPER650) );
1540  break ;
1541  }
1542  case vpRobot::ARTICULAR_FRAME : {
1543  // Convert all the velocities from rad/s into deg/s
1544  vel_sat.rad2deg();
1545  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1546  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER650) );
1547  Try( PrimitiveMOVESPEED_Viper650(vel_sat.data) );
1548  break ;
1549  }
1550  case vpRobot::REFERENCE_FRAME : {
1551  // Send velocities in m/s and rad/s
1552  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1553  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPFIX_VIPER650) );
1554  break ;
1555  }
1556  case vpRobot::MIXT_FRAME : {
1557  //Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPMIX_VIPER650) );
1558  break ;
1559  }
1560  default: {
1561  vpERROR_TRACE ("Error in spec of vpRobot. "
1562  "Case not taken in account.");
1563  return;
1564  }
1565  }
1566 
1567  Catch();
1568  if (TryStt < 0) {
1569  if (TryStt == VelStopOnJoint) {
1570  UInt32 axisInJoint[njoint];
1571  PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1572  for (unsigned int i=0; i < njoint; i ++) {
1573  if (axisInJoint[i])
1574  std::cout << "\nWarning: Velocity control stopped: axis "
1575  << i+1 << " on joint limit!" <<std::endl;
1576  }
1577  }
1578  else {
1579  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1580  if (TryString != NULL) {
1581  // The statement is in TryString, but we need to check the validity
1582  printf(" Error sentence %s\n", TryString); // Print the TryString
1583  }
1584  else {
1585  printf("\n");
1586  }
1587  }
1588  }
1589 
1590  return;
1591 }
1592 
1593 
1594 
1595 
1596 
1597 
1598 /* ------------------------------------------------------------------------ */
1599 /* --- GET ---------------------------------------------------------------- */
1600 /* ------------------------------------------------------------------------ */
1601 
1602 
1660  vpColVector & velocity, double &timestamp)
1661 {
1662  velocity.resize (6);
1663  velocity = 0;
1664 
1665  vpColVector q_cur(6);
1666  vpHomogeneousMatrix fMc_cur;
1667  vpHomogeneousMatrix cMc; // camera displacement
1668  double time_cur;
1669 
1670  InitTry;
1671 
1672  // Get the current joint position
1673  Try( PrimitiveACQ_POS_J_Viper650(q_cur.data, &timestamp) );
1674  time_cur = timestamp;
1675  q_cur.deg2rad();
1676 
1677  // Get the camera pose from the direct kinematics
1678  vpViper650::get_fMc(q_cur, fMc_cur);
1679 
1680  if ( ! first_time_getvel ) {
1681 
1682  switch (frame) {
1683  case vpRobot::CAMERA_FRAME: {
1684  // Compute the displacement of the camera since the previous call
1685  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1686 
1687  // Compute the velocity of the camera from this displacement
1688  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1689 
1690  break ;
1691  }
1692 
1693  case vpRobot::ARTICULAR_FRAME: {
1694  velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1695  break ;
1696  }
1697 
1698  case vpRobot::REFERENCE_FRAME: {
1699  // Compute the displacement of the camera since the previous call
1700  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1701 
1702  // Compute the velocity of the camera from this displacement
1703  vpColVector v;
1704  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1705 
1706  // Express this velocity in the reference frame
1707  vpVelocityTwistMatrix fVc(fMc_cur);
1708  velocity = fVc * v;
1709 
1710  break ;
1711  }
1712 
1713  case vpRobot::MIXT_FRAME: {
1714  // Compute the displacement of the camera since the previous call
1715  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1716 
1717  // Compute the ThetaU representation for the rotation
1718  vpRotationMatrix cRc;
1719  cMc.extract(cRc);
1720  vpThetaUVector thetaU;
1721  thetaU.buildFrom(cRc);
1722 
1723  for (unsigned int i=0; i < 3; i++) {
1724  // Compute the translation displacement in the reference frame
1725  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1726  // Update the rotation displacement in the camera frame
1727  velocity[i+3] = thetaU[i];
1728  }
1729 
1730  // Compute the velocity
1731  velocity /= (time_cur - time_prev_getvel);
1732  break ;
1733  }
1734  }
1735  }
1736  else {
1737  first_time_getvel = false;
1738  }
1739 
1740  // Memorize the camera pose for the next call
1741  fMc_prev_getvel = fMc_cur;
1742 
1743  // Memorize the joint position for the next call
1744  q_prev_getvel = q_cur;
1745 
1746  // Memorize the time associated to the joint position for the next call
1747  time_prev_getvel = time_cur;
1748 
1749 
1750  CatchPrint();
1751  if (TryStt < 0) {
1752  vpERROR_TRACE ("Cannot get velocity.");
1754  "Cannot get velocity.");
1755  }
1756 }
1757 
1767  vpColVector & velocity)
1768 {
1769  double timestamp;
1770  getVelocity(frame, velocity, timestamp);
1771 }
1772 
1824 {
1825  vpColVector velocity;
1826  getVelocity (frame, velocity, timestamp);
1827 
1828  return velocity;
1829 }
1830 
1840 {
1841  vpColVector velocity;
1842  double timestamp;
1843  getVelocity (frame, velocity, timestamp);
1844 
1845  return velocity;
1846 }
1847 
1913 bool vpRobotViper650::readPosFile(const char *filename, vpColVector &q)
1914 {
1915 
1916  FILE * fd ;
1917  fd = fopen(filename, "r") ;
1918  if (fd == NULL)
1919  return false;
1920 
1921  char line[FILENAME_MAX];
1922  char dummy[FILENAME_MAX];
1923  char head[] = "R:";
1924  bool sortie = false;
1925 
1926  do {
1927  // Saut des lignes commencant par #
1928  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1929  if ( strncmp (line, "#", 1) != 0) {
1930  // La ligne n'est pas un commentaire
1931  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1932  sortie = true; // Position robot trouvee.
1933  }
1934  // else
1935  // return (false); // fin fichier sans position robot.
1936  }
1937  }
1938  else {
1939  return (false); /* fin fichier */
1940  }
1941 
1942  }
1943  while ( sortie != true );
1944 
1945  // Lecture des positions
1946  q.resize(njoint);
1947  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1948  dummy,
1949  &q[0], &q[1], &q[2],
1950  &q[3], &q[4], &q[5]);
1951 
1952  // converts rotations from degrees into radians
1953  q.deg2rad();
1954 
1955  fclose(fd) ;
1956  return (true);
1957 }
1958 
1982 bool
1983  vpRobotViper650::savePosFile(const char *filename, const vpColVector &q)
1984 {
1985 
1986  FILE * fd ;
1987  fd = fopen(filename, "w") ;
1988  if (fd == NULL)
1989  return false;
1990 
1991  fprintf(fd, "\
1992 #Viper - Position - Version 1.0\n\
1993 #\n\
1994 # R: A B C D E F\n\
1995 # Joint position in degrees\n\
1996 #\n\
1997 #\n\n");
1998 
1999  // Save positions in mm and deg
2000  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2001  vpMath::deg(q[0]),
2002  vpMath::deg(q[1]),
2003  vpMath::deg(q[2]),
2004  vpMath::deg(q[3]),
2005  vpMath::deg(q[4]),
2006  vpMath::deg(q[5]));
2007 
2008  fclose(fd) ;
2009  return (true);
2010 }
2011 
2022 void
2023  vpRobotViper650::move(const char *filename)
2024 {
2025  vpColVector q;
2026 
2027  try {
2028  this->readPosFile(filename, q) ;
2030  this->setPositioningVelocity(10);
2032  }
2033  catch(...) {
2034  throw;
2035  }
2036 }
2037 
2051 void
2052  vpRobotViper650::getCameraDisplacement(vpColVector &displacement)
2053 {
2054  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2055 }
2067 void
2068  vpRobotViper650::getArticularDisplacement(vpColVector &displacement)
2069 {
2071 }
2072 
2093 void
2095  vpColVector &displacement)
2096 {
2097  displacement.resize (6);
2098  displacement = 0;
2099 
2100  double q[6];
2101  vpColVector q_cur(6);
2102  double timestamp;
2103 
2104  InitTry;
2105 
2106  // Get the current joint position
2107  Try( PrimitiveACQ_POS_Viper650(q, &timestamp) );
2108  for (unsigned int i=0; i < njoint; i ++) {
2109  q_cur[i] = q[i];
2110  }
2111 
2112  if ( ! first_time_getdis ) {
2113  switch (frame) {
2114  case vpRobot::CAMERA_FRAME: {
2115  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2116  return;
2117  break ;
2118  }
2119 
2120  case vpRobot::ARTICULAR_FRAME: {
2121  displacement = q_cur - q_prev_getdis;
2122  break ;
2123  }
2124 
2125  case vpRobot::REFERENCE_FRAME: {
2126  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2127  return;
2128  break ;
2129  }
2130 
2131  case vpRobot::MIXT_FRAME: {
2132  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2133  return;
2134  break ;
2135  }
2136  }
2137  }
2138  else {
2139  first_time_getdis = false;
2140  }
2141 
2142  // Memorize the joint position for the next call
2143  q_prev_getdis = q_cur;
2144 
2145  CatchPrint();
2146  if (TryStt < 0) {
2147  vpERROR_TRACE ("Cannot get velocity.");
2149  "Cannot get velocity.");
2150  }
2151 }
2152 
2166 void
2168 {
2169  InitTry;
2170 
2171  Try( PrimitiveTFS_BIAS_Viper650() );
2172 
2173  // Wait 500 ms to be sure the next measures take into account the bias
2174  vpTime::wait(500);
2175 
2176  CatchPrint();
2177  if (TryStt < 0) {
2178  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2180  "Cannot bias the force/torque sensor.");
2181  }
2182 }
2183 
2223 void
2225 {
2226  InitTry;
2227 
2228  H.resize (6);
2229 
2230  Try( PrimitiveTFS_ACQ_Viper650(H.data) );
2231 
2232  CatchPrint();
2233  if (TryStt < 0) {
2234  vpERROR_TRACE ("Cannot get the force/torque measures.");
2236  "Cannot get force/torque measures.");
2237  }
2238 }
2239 
2240 #endif
2241 
static const double defaultPositioningVelocity
static vpColVector inverse(const vpHomogeneousMatrix &M)
Definition of the vpMatrix class.
Definition: vpMatrix.h:96
Error that can be emited by the vpRobot class and its derivates.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
virtual ~vpRobotViper650(void)
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
#define vpERROR_TRACE
Definition: vpDebug.h:379
void get_eJe(const vpColVector &q, vpMatrix &eJe)
Definition: vpViper.cpp:968
void setVerbose(bool verbose)
Definition: vpRobot.h:155
void setPositioningVelocity(const double velocity)
virtual vpRobotStateType getRobotState(void)
Definition: vpRobot.h:139
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:203
Initialize the position controller.
Definition: vpRobot.h:71
class that defines a generic virtual robot
Definition: vpRobot.h:60
Automatic control mode (default).
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:116
vpControlFrameType
Definition: vpRobot.h:78
vpRxyzVector erc
Definition: vpViper.h:150
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
static int wait(double t0, double t)
Definition: vpTime.cpp:149
void move(const char *filename)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:228
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:154
void deg2rad()
Definition: vpColVector.h:187
double getTime() const
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q)
Definition: vpViper.cpp:559
The vpRotationMatrix considers the particular case of a rotation matrix.
double * data
address of the first element of the data array
Definition: vpMatrix.h:116
double getPositioningVelocity(void)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper650.h:99
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Initialize the velocity controller.
Definition: vpRobot.h:70
Emergency stop activated.
vpRobotStateType
Definition: vpRobot.h:66
bool verbose_
Definition: vpRobot.h:115
vpTranslationVector etc
Definition: vpViper.h:149
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRowVector t() const
transpose of Vector
vpColVector joint_max
Definition: vpViper.h:161
Modelisation of the ADEPT Viper 650 robot.
Definition: vpViper650.h:66
void extract(vpRotationMatrix &R) const
Manual control mode activated when the dead man switch is in use.
void init(void)
Definition: vpViper650.cpp:174
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:91
static double rad(double deg)
Definition: vpMath.h:100
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpViper.cpp:1160
void get_fJe(vpMatrix &fJe)
void get_cMe(vpHomogeneousMatrix &cMe)
static bool savePosFile(const char *filename, const vpColVector &q)
void getForceTorque(vpColVector &H)
static double deg(double rad)
Definition: vpMath.h:93
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
static bool readPosFile(const char *filename, vpColVector &q)
The pose is a complete representation of every rigid motion in the euclidian space.
Definition: vpPoseVector.h:92
vpHomogeneousMatrix inverse() const
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpViper.cpp:914
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
Definition: vpRxyzVector.h:152
Class that consider the case of the Euler angles using the z-y-z convention, where are respectively...
Definition: vpRzyzVector.h:150
void setToolType(vpViper650::vpToolType tool)
Set the current tool type.
Definition: vpViper650.h:136
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
Class that consider the case of a translation vector.
Class that consider the case of the parameterization for the rotation.
void rad2deg()
Definition: vpColVector.h:177
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:597
void get_eJe(vpMatrix &eJe)
void get_cVe(vpVelocityTwistMatrix &cVe)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:94
vpColVector joint_min
Definition: vpViper.h:162