ViSP  2.8.0
vpRobotViper650.cpp
1 /****************************************************************************
2  *
3  * $Id: vpRobotViper650.cpp 4218 2013-04-17 09:55:47Z 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  // Enable the joint limits on axis 6
275  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
276 
277  // Update the eMc matrix in the low level controller
279 
280  // Look if the power is on or off
281  UInt32 HIPowerStatus;
282  UInt32 EStopStatus;
283  Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
284  &HIPowerStatus));
285  CAL_Wait(0.1);
286 
287  // Print the robot status
288  if (verbose_) {
289  std::cout << "Robot status: ";
290  switch(EStopStatus) {
291  case ESTOP_AUTO:
292  controlMode = AUTO;
293  if (HIPowerStatus == 0)
294  std::cout << "Power is OFF" << std::endl;
295  else
296  std::cout << "Power is ON" << std::endl;
297  break;
298 
299  case ESTOP_MANUAL:
300  controlMode = MANUAL;
301  if (HIPowerStatus == 0)
302  std::cout << "Power is OFF" << std::endl;
303  else
304  std::cout << "Power is ON" << std::endl;
305  break;
306  case ESTOP_ACTIVATED:
307  controlMode = ESTOP;
308  std::cout << "Emergency stop is activated" << std::endl;
309  break;
310  default:
311  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
312  std::cout << "You have to call Adept for maintenance..." << std::endl;
313  // Free allocated resources
314  }
315  std::cout << std::endl;
316  }
317  // get real joint min/max from the MotionBlox
318  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
319  // Convert units from degrees to radians
320  joint_min.deg2rad();
321  joint_max.deg2rad();
322 
323  // for (unsigned int i=0; i < njoint; i++) {
324  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
325  // }
326 
327  // If an error occur in the low level controller, goto here
328  //CatchPrint();
329  Catch();
330 
331  // Test if an error occurs
332  if (TryStt == -20001)
333  printf("No connection detected. Check if the robot is powered on \n"
334  "and if the firewire link exist between the MotionBlox and this computer.\n");
335  else if (TryStt == -675)
336  printf(" Timeout enabling power...\n");
337 
338  if (TryStt < 0) {
339  // Power off the robot
340  PrimitivePOWEROFF_Viper650();
341  // Free allocated resources
342  ShutDownConnection();
343 
344  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
346  "Cannot open connexion with the motionblox");
347  }
348  return ;
349 }
350 
407 void
410 {
411 
412  InitTry;
413  // Read the robot constants from files
414  // - joint [min,max], coupl_56, long_56
415  // - camera extrinsic parameters relative to eMc
416  vpViper650::init(tool, projModel);
417 
418  // Set the camera constant (eMc pose) in the MotionBlox
419  double eMc_pose[6];
420  for (unsigned int i=0; i < 3; i ++) {
421  eMc_pose[i] = etc[i]; // translation in meters
422  eMc_pose[i+3] = erc[i]; // rotation in rad
423  }
424  // Update the eMc pose in the low level controller
425  Try( PrimitiveCONST_Viper650(eMc_pose) );
426 
427  // get real joint min/max from the MotionBlox
428  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
429  // Convert units from degrees to radians
430  joint_min.deg2rad();
431  joint_max.deg2rad();
432 
433  // for (unsigned int i=0; i < njoint; i++) {
434  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
435  // }
436 
437  setToolType(tool);
438 
439  CatchPrint();
440  return ;
441 }
442 
443 /* ------------------------------------------------------------------------ */
444 /* --- DESTRUCTOR --------------------------------------------------------- */
445 /* ------------------------------------------------------------------------ */
446 
454 {
455  InitTry;
456 
458 
459  // Look if the power is on or off
460  UInt32 HIPowerStatus;
461  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
462  &HIPowerStatus));
463  CAL_Wait(0.1);
464 
465  // if (HIPowerStatus == 1) {
466  // fprintf(stdout, "Power OFF the robot\n");
467  // fflush(stdout);
468 
469  // Try( PrimitivePOWEROFF_Viper650() );
470  // }
471 
472  // Free allocated resources
473  ShutDownConnection();
474 
475  vpRobotViper650::robotAlreadyCreated = false;
476 
477  CatchPrint();
478  return;
479 }
480 
481 
482 
483 
492 {
493  InitTry;
494 
495  switch (newState) {
496  case vpRobot::STATE_STOP: {
497  // Start primitive STOP only if the current state is Velocity
499  Try( PrimitiveSTOP_Viper650() );
500  }
501  break;
502  }
505  std::cout << "Change the control mode from velocity to position control.\n";
506  Try( PrimitiveSTOP_Viper650() );
507  }
508  else {
509  //std::cout << "Change the control mode from stop to position control.\n";
510  }
511  this->powerOn();
512  break;
513  }
516  std::cout << "Change the control mode from stop to velocity control.\n";
517  }
518  this->powerOn();
519  break;
520  }
521  default:
522  break ;
523  }
524 
525  CatchPrint();
526 
527  return vpRobot::setRobotState (newState);
528 }
529 
530 
531 /* ------------------------------------------------------------------------ */
532 /* --- STOP --------------------------------------------------------------- */
533 /* ------------------------------------------------------------------------ */
534 
542 void
544 {
546  return;
547 
548  InitTry;
549  Try( PrimitiveSTOP_Viper650() );
551 
552  CatchPrint();
553  if (TryStt < 0) {
554  vpERROR_TRACE ("Cannot stop robot motion");
556  "Cannot stop robot motion.");
557  }
558 }
559 
569 void
571 {
572  InitTry;
573 
574  // Look if the power is on or off
575  UInt32 HIPowerStatus;
576  UInt32 EStopStatus;
577  bool firsttime = true;
578  unsigned int nitermax = 10;
579 
580  for (unsigned int i=0; i<nitermax; i++) {
581  Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
582  &HIPowerStatus));
583  if (EStopStatus == ESTOP_AUTO) {
584  controlMode = AUTO;
585  break; // exit for loop
586  }
587  else if (EStopStatus == ESTOP_MANUAL) {
588  controlMode = MANUAL;
589  break; // exit for loop
590  }
591  else if (EStopStatus == ESTOP_ACTIVATED) {
592  controlMode = ESTOP;
593  if (firsttime) {
594  std::cout << "Emergency stop is activated! \n"
595  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
596  firsttime = false;
597  }
598  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
599  fflush(stdout);
600  CAL_Wait(1);
601  }
602  else {
603  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
604  std::cout << "You have to call Adept for maintenance..." << std::endl;
605  // Free allocated resources
606  ShutDownConnection();
607  exit(0);
608  }
609  }
610 
611  if (EStopStatus == ESTOP_ACTIVATED)
612  std::cout << std::endl;
613 
614  if (EStopStatus == ESTOP_ACTIVATED) {
615  std::cout << "Sorry, cannot power on the robot." << std::endl;
617  "Cannot power on the robot.");
618  }
619 
620  if (HIPowerStatus == 0) {
621  fprintf(stdout, "Power ON the Viper650 robot\n");
622  fflush(stdout);
623 
624  Try( PrimitivePOWERON_Viper650() );
625  }
626 
627  CatchPrint();
628  if (TryStt < 0) {
629  vpERROR_TRACE ("Cannot power on the robot");
631  "Cannot power off the robot.");
632  }
633 }
634 
644 void
646 {
647  InitTry;
648 
649  // Look if the power is on or off
650  UInt32 HIPowerStatus;
651  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
652  &HIPowerStatus));
653  CAL_Wait(0.1);
654 
655  if (HIPowerStatus == 1) {
656  fprintf(stdout, "Power OFF the Viper650 robot\n");
657  fflush(stdout);
658 
659  Try( PrimitivePOWEROFF_Viper650() );
660  }
661 
662  CatchPrint();
663  if (TryStt < 0) {
664  vpERROR_TRACE ("Cannot power off the robot");
666  "Cannot power off the robot.");
667  }
668 }
669 
681 bool
683 {
684  InitTry;
685  bool status = false;
686  // Look if the power is on or off
687  UInt32 HIPowerStatus;
688  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
689  &HIPowerStatus));
690  CAL_Wait(0.1);
691 
692  if (HIPowerStatus == 1) {
693  status = true;
694  }
695 
696  CatchPrint();
697  if (TryStt < 0) {
698  vpERROR_TRACE ("Cannot get the power status");
700  "Cannot get the power status.");
701  }
702  return status;
703 }
704 
714 void
716 {
717  vpHomogeneousMatrix cMe ;
718  vpViper650::get_cMe(cMe) ;
719 
720  cVe.buildFrom(cMe) ;
721 }
722 
734 void
736 {
737  vpViper650::get_cMe(cMe) ;
738 }
739 
740 
752 void
754 {
755 
756  double position[6];
757  double timestamp;
758 
759  InitTry;
760  Try( PrimitiveACQ_POS_J_Viper650(position, &timestamp) );
761  CatchPrint();
762 
763  vpColVector q(6);
764  for (unsigned int i=0; i < njoint; i++)
765  q[i] = vpMath::rad(position[i]);
766 
767  try
768  {
769  vpViper650::get_eJe(q, eJe) ;
770  }
771  catch(...)
772  {
773  vpERROR_TRACE("catch exception ") ;
774  throw ;
775  }
776 }
789 void
791 {
792 
793  double position[6];
794  double timestamp;
795 
796  InitTry;
797  Try( PrimitiveACQ_POS_Viper650(position, &timestamp) );
798  CatchPrint();
799 
800  vpColVector q(6);
801  for (unsigned int i=0; i < njoint; i++)
802  q[i] = position[i];
803 
804  try
805  {
806  vpViper650::get_fJe(q, fJe) ;
807  }
808  catch(...)
809  {
810  vpERROR_TRACE("Error caught");
811  throw ;
812  }
813 }
814 
852 void
854 {
855  positioningVelocity = velocity;
856 }
857 
863 double
865 {
866  return positioningVelocity;
867 }
868 
869 
947 void
949  const vpColVector & position )
950 {
951 
953  {
954  vpERROR_TRACE ("Robot was not in position-based control\n"
955  "Modification of the robot state");
957  }
958 
959  vpColVector destination(njoint);
960  int error = 0;
961  double timestamp;
962 
963  InitTry;
964  switch(frame) {
965  case vpRobot::CAMERA_FRAME : {
966  vpColVector q(njoint);
967  Try( PrimitiveACQ_POS_Viper650(q.data, &timestamp) );
968 
969  // Convert degrees into rad
970  q.deg2rad();
971 
972  // Get fMc from the inverse kinematics
974  vpViper650::get_fMc(q, fMc);
975 
976  // Set cMc from the input position
977  vpTranslationVector txyz;
978  vpRxyzVector rxyz;
979  for (unsigned int i=0; i < 3; i++) {
980  txyz[i] = position[i];
981  rxyz[i] = position[i+3];
982  }
983 
984  // Compute cMc2
985  vpRotationMatrix cRc2(rxyz);
986  vpHomogeneousMatrix cMc2(txyz, cRc2);
987 
988  // Compute the new position to reach: fMc*cMc2
989  vpHomogeneousMatrix fMc2 = fMc * cMc2;
990 
991  // Compute the corresponding joint position from the inverse kinematics
992  unsigned int solution = this->getInverseKinematics(fMc2, q);
993  if (solution) { // Position is reachable
994  destination = q;
995  // convert rad to deg requested for the low level controller
996  destination.rad2deg();
997  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
998  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
999  }
1000  else {
1001  // Cartesian position is out of range
1002  error = -1;
1003  }
1004 
1005  break ;
1006  }
1007  case vpRobot::ARTICULAR_FRAME: {
1008  destination = position;
1009  // convert rad to deg requested for the low level controller
1010  destination.rad2deg();
1011 
1012  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1013  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
1014  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1015  break ;
1016 
1017  }
1018  case vpRobot::REFERENCE_FRAME: {
1019  // Convert angles from Rxyz representation to Rzyz representation
1020  vpRxyzVector rxyz(position[3],position[4],position[5]);
1021  vpRotationMatrix R(rxyz);
1022  vpRzyzVector rzyz(R);
1023 
1024  for (unsigned int i=0; i <3; i++) {
1025  destination[i] = position[i];
1026  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1027  }
1028  int configuration = 0; // keep the actual configuration
1029 
1030  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1031  Try( PrimitiveMOVE_C_Viper650(destination.data, configuration,
1032  positioningVelocity) );
1033  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1034 
1035  break ;
1036  }
1037  case vpRobot::MIXT_FRAME:
1038  {
1039  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1041  "Positionning error: "
1042  "Mixt frame not implemented.");
1043  break ;
1044  }
1045  }
1046 
1047  CatchPrint();
1048  if (TryStt == InvalidPosition || TryStt == -1023)
1049  std::cout << " : Position out of range.\n";
1050 
1051  else if (TryStt == -3019) {
1052  if (frame == vpRobot::ARTICULAR_FRAME)
1053  std::cout << " : Joint position out of range.\n";
1054  else
1055  std::cout << " : Cartesian position leads to a joint position out of range.\n";
1056  }
1057  else if (TryStt < 0)
1058  std::cout << " : Unknown error (see Fabien).\n";
1059  else if (error == -1)
1060  std::cout << "Position out of range.\n";
1061 
1062  if (TryStt < 0 || error < 0) {
1063  vpERROR_TRACE ("Positionning error.");
1065  "Position out of range.");
1066  }
1067 
1068  return ;
1069 }
1070 
1137  const double pos1,
1138  const double pos2,
1139  const double pos3,
1140  const double pos4,
1141  const double pos5,
1142  const double pos6)
1143 {
1144  try{
1145  vpColVector position(6) ;
1146  position[0] = pos1 ;
1147  position[1] = pos2 ;
1148  position[2] = pos3 ;
1149  position[3] = pos4 ;
1150  position[4] = pos5 ;
1151  position[5] = pos6 ;
1152 
1153  setPosition(frame, position) ;
1154  }
1155  catch(...)
1156  {
1157  vpERROR_TRACE("Error caught");
1158  throw ;
1159  }
1160 }
1161 
1201 void vpRobotViper650::setPosition(const char *filename)
1202 {
1203  vpColVector q;
1204  bool ret;
1205 
1206  ret = this->readPosFile(filename, q);
1207 
1208  if (ret == false) {
1209  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1211  "Bad position in filename.");
1212  }
1215 }
1216 
1286  vpColVector &position,
1287  double &timestamp)
1288 {
1289 
1290  InitTry;
1291 
1292  position.resize (6);
1293 
1294  switch (frame) {
1295  case vpRobot::CAMERA_FRAME : {
1296  position = 0;
1297  return;
1298  }
1299  case vpRobot::ARTICULAR_FRAME : {
1300  Try( PrimitiveACQ_POS_J_Viper650(position.data, &timestamp) );
1301  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1302  position.deg2rad();
1303 
1304  return;
1305  }
1306  case vpRobot::REFERENCE_FRAME : {
1307  Try( PrimitiveACQ_POS_C_Viper650(position.data, &timestamp) );
1308  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1309  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1310  // Convert Euler Rzyz angles from deg to rad
1311  for (unsigned int i=3; i <6; i++)
1312  position[i] = vpMath::rad(position[i]);
1313  // Convert Rzyz angles into Rxyz representation
1314  vpRzyzVector rzyz(position[3], position[4], position[5]);
1315  vpRotationMatrix R(rzyz);
1316  vpRxyzVector rxyz(R);
1317 
1318  // Update the position using Rxyz representation
1319  for (unsigned int i=0; i <3; i++)
1320  position[i+3] = rxyz[i];
1321  // vpCTRACE << "Cartesian position Rxyz (deg)"
1322  // << position[0] << " " << position[1] << " " << position[2] << " "
1323  // << vpMath::deg(position[3]) << " "
1324  // << vpMath::deg(position[4]) << " "
1325  // << vpMath::deg(position[5]) << std::endl;
1326 
1327  break ;
1328  }
1329  case vpRobot::MIXT_FRAME: {
1330  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1332  "Cannot get position in mixt frame: "
1333  "not implemented");
1334  break ;
1335  }
1336  }
1337 
1338  CatchPrint();
1339  if (TryStt < 0) {
1340  vpERROR_TRACE ("Cannot get position.");
1342  "Cannot get position.");
1343  }
1344 
1345  return;
1346 }
1347 
1358  vpColVector &position)
1359 {
1360  double timestamp;
1361  getPosition(frame, position, timestamp);
1362 }
1363 
1376  vpPoseVector &position,
1377  double &timestamp)
1378 {
1379  vpColVector posRxyz;
1380  //recupere position en Rxyz
1381  this->getPosition(frame, posRxyz, timestamp);
1382  vpRxyzVector RxyzVect;
1383  for (unsigned int j=0;j<3;j++)
1384  RxyzVect[j]=posRxyz[j+3];
1385  //recupere le vecteur thetaU correspondant
1386  vpThetaUVector RtuVect(RxyzVect);
1387 
1388  //remplit le vpPoseVector avec translation et rotation ThetaU
1389  for (unsigned int j=0;j<3;j++)
1390  {
1391  position[j]=posRxyz[j];
1392  position[j+3]=RtuVect[j];
1393  }
1394 }
1395 
1406  vpPoseVector &position)
1407 {
1408  double timestamp;
1409  getPosition(frame, position, timestamp);
1410 }
1411 
1416 {
1417  double timestamp;
1418  PrimitiveACQ_TIME_Viper650(&timestamp);
1419  return timestamp;
1420 }
1421 
1494 void
1496  const vpColVector & vel)
1497 {
1499  vpERROR_TRACE ("Cannot send a velocity to the robot "
1500  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1502  "Cannot send a velocity to the robot "
1503  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1504  }
1505 
1506  vpColVector vel_sat(6);
1507 
1508  // Velocity saturation
1509  switch(frame) {
1510  // saturation in cartesian space
1511  case vpRobot::CAMERA_FRAME :
1513  case vpRobot::MIXT_FRAME : {
1514  vpColVector vel_max(6);
1515 
1516  for (unsigned int i=0; i<3; i++)
1517  vel_max[i] = getMaxTranslationVelocity();
1518  for (unsigned int i=3; i<6; i++)
1519  vel_max[i] = getMaxRotationVelocity();
1520 
1521  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1522 
1523  break;
1524  }
1525  // saturation in joint space
1526  case vpRobot::ARTICULAR_FRAME : {
1527  vpColVector vel_max(6);
1528 
1529  for (unsigned int i=0; i<6; i++)
1530  vel_max[i] = getMaxRotationVelocity();
1531 
1532  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1533  }
1534  }
1535 
1536  InitTry;
1537 
1538  switch(frame) {
1539  case vpRobot::CAMERA_FRAME : {
1540  // Send velocities in m/s and rad/s
1541  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1542  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPCAM_VIPER650) );
1543  break ;
1544  }
1545  case vpRobot::ARTICULAR_FRAME : {
1546  // Convert all the velocities from rad/s into deg/s
1547  vel_sat.rad2deg();
1548  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1549  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER650) );
1550  Try( PrimitiveMOVESPEED_Viper650(vel_sat.data) );
1551  break ;
1552  }
1553  case vpRobot::REFERENCE_FRAME : {
1554  // Send velocities in m/s and rad/s
1555  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1556  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPFIX_VIPER650) );
1557  break ;
1558  }
1559  case vpRobot::MIXT_FRAME : {
1560  //Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPMIX_VIPER650) );
1561  break ;
1562  }
1563  default: {
1564  vpERROR_TRACE ("Error in spec of vpRobot. "
1565  "Case not taken in account.");
1566  return;
1567  }
1568  }
1569 
1570  Catch();
1571  if (TryStt < 0) {
1572  if (TryStt == VelStopOnJoint) {
1573  UInt32 axisInJoint[njoint];
1574  PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1575  for (unsigned int i=0; i < njoint; i ++) {
1576  if (axisInJoint[i])
1577  std::cout << "\nWarning: Velocity control stopped: axis "
1578  << i+1 << " on joint limit!" <<std::endl;
1579  }
1580  }
1581  else {
1582  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1583  if (TryString != NULL) {
1584  // The statement is in TryString, but we need to check the validity
1585  printf(" Error sentence %s\n", TryString); // Print the TryString
1586  }
1587  else {
1588  printf("\n");
1589  }
1590  }
1591  }
1592 
1593  return;
1594 }
1595 
1596 
1597 
1598 
1599 
1600 
1601 /* ------------------------------------------------------------------------ */
1602 /* --- GET ---------------------------------------------------------------- */
1603 /* ------------------------------------------------------------------------ */
1604 
1605 
1663  vpColVector & velocity, double &timestamp)
1664 {
1665  velocity.resize (6);
1666  velocity = 0;
1667 
1668  vpColVector q_cur(6);
1669  vpHomogeneousMatrix fMc_cur;
1670  vpHomogeneousMatrix cMc; // camera displacement
1671  double time_cur;
1672 
1673  InitTry;
1674 
1675  // Get the current joint position
1676  Try( PrimitiveACQ_POS_J_Viper650(q_cur.data, &timestamp) );
1677  time_cur = timestamp;
1678  q_cur.deg2rad();
1679 
1680  // Get the camera pose from the direct kinematics
1681  vpViper650::get_fMc(q_cur, fMc_cur);
1682 
1683  if ( ! first_time_getvel ) {
1684 
1685  switch (frame) {
1686  case vpRobot::CAMERA_FRAME: {
1687  // Compute the displacement of the camera since the previous call
1688  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1689 
1690  // Compute the velocity of the camera from this displacement
1691  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1692 
1693  break ;
1694  }
1695 
1696  case vpRobot::ARTICULAR_FRAME: {
1697  velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1698  break ;
1699  }
1700 
1701  case vpRobot::REFERENCE_FRAME: {
1702  // Compute the displacement of the camera since the previous call
1703  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1704 
1705  // Compute the velocity of the camera from this displacement
1706  vpColVector v;
1707  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1708 
1709  // Express this velocity in the reference frame
1710  vpVelocityTwistMatrix fVc(fMc_cur);
1711  velocity = fVc * v;
1712 
1713  break ;
1714  }
1715 
1716  case vpRobot::MIXT_FRAME: {
1717  // Compute the displacement of the camera since the previous call
1718  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1719 
1720  // Compute the ThetaU representation for the rotation
1721  vpRotationMatrix cRc;
1722  cMc.extract(cRc);
1723  vpThetaUVector thetaU;
1724  thetaU.buildFrom(cRc);
1725 
1726  for (unsigned int i=0; i < 3; i++) {
1727  // Compute the translation displacement in the reference frame
1728  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1729  // Update the rotation displacement in the camera frame
1730  velocity[i+3] = thetaU[i];
1731  }
1732 
1733  // Compute the velocity
1734  velocity /= (time_cur - time_prev_getvel);
1735  break ;
1736  }
1737  }
1738  }
1739  else {
1740  first_time_getvel = false;
1741  }
1742 
1743  // Memorize the camera pose for the next call
1744  fMc_prev_getvel = fMc_cur;
1745 
1746  // Memorize the joint position for the next call
1747  q_prev_getvel = q_cur;
1748 
1749  // Memorize the time associated to the joint position for the next call
1750  time_prev_getvel = time_cur;
1751 
1752 
1753  CatchPrint();
1754  if (TryStt < 0) {
1755  vpERROR_TRACE ("Cannot get velocity.");
1757  "Cannot get velocity.");
1758  }
1759 }
1760 
1770  vpColVector & velocity)
1771 {
1772  double timestamp;
1773  getVelocity(frame, velocity, timestamp);
1774 }
1775 
1827 {
1828  vpColVector velocity;
1829  getVelocity (frame, velocity, timestamp);
1830 
1831  return velocity;
1832 }
1833 
1843 {
1844  vpColVector velocity;
1845  double timestamp;
1846  getVelocity (frame, velocity, timestamp);
1847 
1848  return velocity;
1849 }
1850 
1916 bool vpRobotViper650::readPosFile(const char *filename, vpColVector &q)
1917 {
1918 
1919  FILE * fd ;
1920  fd = fopen(filename, "r") ;
1921  if (fd == NULL)
1922  return false;
1923 
1924  char line[FILENAME_MAX];
1925  char dummy[FILENAME_MAX];
1926  char head[] = "R:";
1927  bool sortie = false;
1928 
1929  do {
1930  // Saut des lignes commencant par #
1931  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1932  if ( strncmp (line, "#", 1) != 0) {
1933  // La ligne n'est pas un commentaire
1934  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1935  sortie = true; // Position robot trouvee.
1936  }
1937  // else
1938  // return (false); // fin fichier sans position robot.
1939  }
1940  }
1941  else {
1942  return (false); /* fin fichier */
1943  }
1944 
1945  }
1946  while ( sortie != true );
1947 
1948  // Lecture des positions
1949  q.resize(njoint);
1950  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1951  dummy,
1952  &q[0], &q[1], &q[2],
1953  &q[3], &q[4], &q[5]);
1954 
1955  // converts rotations from degrees into radians
1956  q.deg2rad();
1957 
1958  fclose(fd) ;
1959  return (true);
1960 }
1961 
1985 bool
1986  vpRobotViper650::savePosFile(const char *filename, const vpColVector &q)
1987 {
1988 
1989  FILE * fd ;
1990  fd = fopen(filename, "w") ;
1991  if (fd == NULL)
1992  return false;
1993 
1994  fprintf(fd, "\
1995 #Viper - Position - Version 1.0\n\
1996 #\n\
1997 # R: A B C D E F\n\
1998 # Joint position in degrees\n\
1999 #\n\
2000 #\n\n");
2001 
2002  // Save positions in mm and deg
2003  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2004  vpMath::deg(q[0]),
2005  vpMath::deg(q[1]),
2006  vpMath::deg(q[2]),
2007  vpMath::deg(q[3]),
2008  vpMath::deg(q[4]),
2009  vpMath::deg(q[5]));
2010 
2011  fclose(fd) ;
2012  return (true);
2013 }
2014 
2025 void
2026  vpRobotViper650::move(const char *filename)
2027 {
2028  vpColVector q;
2029 
2030  try {
2031  this->readPosFile(filename, q) ;
2033  this->setPositioningVelocity(10);
2035  }
2036  catch(...) {
2037  throw;
2038  }
2039 }
2040 
2054 void
2055  vpRobotViper650::getCameraDisplacement(vpColVector &displacement)
2056 {
2057  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2058 }
2070 void
2071  vpRobotViper650::getArticularDisplacement(vpColVector &displacement)
2072 {
2074 }
2075 
2096 void
2098  vpColVector &displacement)
2099 {
2100  displacement.resize (6);
2101  displacement = 0;
2102 
2103  double q[6];
2104  vpColVector q_cur(6);
2105  double timestamp;
2106 
2107  InitTry;
2108 
2109  // Get the current joint position
2110  Try( PrimitiveACQ_POS_Viper650(q, &timestamp) );
2111  for (unsigned int i=0; i < njoint; i ++) {
2112  q_cur[i] = q[i];
2113  }
2114 
2115  if ( ! first_time_getdis ) {
2116  switch (frame) {
2117  case vpRobot::CAMERA_FRAME: {
2118  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2119  return;
2120  break ;
2121  }
2122 
2123  case vpRobot::ARTICULAR_FRAME: {
2124  displacement = q_cur - q_prev_getdis;
2125  break ;
2126  }
2127 
2128  case vpRobot::REFERENCE_FRAME: {
2129  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2130  return;
2131  break ;
2132  }
2133 
2134  case vpRobot::MIXT_FRAME: {
2135  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2136  return;
2137  break ;
2138  }
2139  }
2140  }
2141  else {
2142  first_time_getdis = false;
2143  }
2144 
2145  // Memorize the joint position for the next call
2146  q_prev_getdis = q_cur;
2147 
2148  CatchPrint();
2149  if (TryStt < 0) {
2150  vpERROR_TRACE ("Cannot get velocity.");
2152  "Cannot get velocity.");
2153  }
2154 }
2155 
2169 void
2171 {
2172  InitTry;
2173 
2174  Try( PrimitiveTFS_BIAS_Viper650() );
2175 
2176  // Wait 500 ms to be sure the next measures take into account the bias
2177  vpTime::wait(500);
2178 
2179  CatchPrint();
2180  if (TryStt < 0) {
2181  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2183  "Cannot bias the force/torque sensor.");
2184  }
2185 }
2186 
2226 void
2228 {
2229  InitTry;
2230 
2231  H.resize (6);
2232 
2233  Try( PrimitiveTFS_ACQ_Viper650(H.data) );
2234 
2235  CatchPrint();
2236  if (TryStt < 0) {
2237  vpERROR_TRACE ("Cannot get the force/torque measures.");
2239  "Cannot get force/torque measures.");
2240  }
2241 }
2242 
2249 {
2250  InitTry;
2251  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
2252  std::cout << "Enable joint limits on axis 6..." << std::endl;
2253  CatchPrint();
2254  if (TryStt < 0) {
2255  vpERROR_TRACE ("Cannot enable joint limits on axis 6");
2257  "Cannot enable joint limits on axis 6.");
2258  }
2259 }
2260 
2271 {
2272  InitTry;
2273  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1) );
2274  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2275  CatchPrint();
2276  if (TryStt < 0) {
2277  vpERROR_TRACE ("Cannot disable joint limits on axis 6");
2279  "Cannot disable joint limits on axis 6.");
2280  }
2281 }
2282 #endif
2283 
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:985
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
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:1177
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:931
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
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false)
Definition: vpViper.cpp:576
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:614
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