ViSP  2.7.0
vpRobotViper850.cpp
1 /****************************************************************************
2  *
3  * $Id: vpRobotViper850.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 S850 robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
42 #include <visp/vpConfig.h>
43 
44 #ifdef VISP_HAVE_VIPER850
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/vpRobotViper850.h>
58 
59 /* ---------------------------------------------------------------------- */
60 /* --- STATIC ----------------------------------------------------------- */
61 /* ---------------------------------------------------------------------- */
62 
63 bool vpRobotViper850::robotAlreadyCreated = false;
64 
73 
74 /* ---------------------------------------------------------------------- */
75 /* --- EMERGENCY STOP --------------------------------------------------- */
76 /* ---------------------------------------------------------------------- */
77 
85 void emergencyStopViper850(int signo)
86 {
87  std::cout << "Stop the Viper850 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_Viper850();
106  PrimitiveSTOP_Viper850();
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 vpRobotViper850::vpRobotViper850 (bool verbose)
178  :
179  vpViper850 (),
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, emergencyStopViper850);
203  signal(SIGBUS, emergencyStopViper850) ;
204  signal(SIGSEGV, emergencyStopViper850) ;
205  signal(SIGKILL, emergencyStopViper850);
206  signal(SIGQUIT, emergencyStopViper850);
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  vpRobotViper850::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 
267  // Initialize the firewire connection
268  Try( InitializeConnection(verbose_) );
269 
270  // Connect to the servoboard using the servo board GUID
271  Try( InitializeNode_Viper850() );
272 
273  Try( PrimitiveRESET_Viper850() );
274 
275  // Update the eMc matrix in the low level controller
277 
278  // Look if the power is on or off
279  UInt32 HIPowerStatus;
280  UInt32 EStopStatus;
281  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
282  &HIPowerStatus));
283  CAL_Wait(0.1);
284 
285  // Print the robot status
286  if (verbose_) {
287  std::cout << "Robot status: ";
288  switch(EStopStatus) {
289  case ESTOP_AUTO:
290  controlMode = AUTO;
291  if (HIPowerStatus == 0)
292  std::cout << "Power is OFF" << std::endl;
293  else
294  std::cout << "Power is ON" << std::endl;
295  break;
296 
297  case ESTOP_MANUAL:
298  controlMode = MANUAL;
299  if (HIPowerStatus == 0)
300  std::cout << "Power is OFF" << std::endl;
301  else
302  std::cout << "Power is ON" << std::endl;
303  break;
304  case ESTOP_ACTIVATED:
305  controlMode = ESTOP;
306  std::cout << "Emergency stop is activated" << std::endl;
307  break;
308  default:
309  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
310  std::cout << "You have to call Adept for maintenance..." << std::endl;
311  // Free allocated resources
312  }
313  std::cout << std::endl;
314  }
315  // get real joint min/max from the MotionBlox
316  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
317  // Convert units from degrees to radians
318  joint_min.deg2rad();
319  joint_max.deg2rad();
320 
321  // for (unsigned int i=0; i < njoint; i++) {
322  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
323  // }
324 
325  // If an error occur in the low level controller, goto here
326  //CatchPrint();
327  Catch();
328 
329  // Test if an error occurs
330  if (TryStt == -20001)
331  printf("No connection detected. Check if the robot is powered on \n"
332  "and if the firewire link exist between the MotionBlox and this computer.\n");
333  else if (TryStt == -675)
334  printf(" Timeout enabling power...\n");
335 
336  if (TryStt < 0) {
337  // Power off the robot
338  PrimitivePOWEROFF_Viper850();
339  // Free allocated resources
340  ShutDownConnection();
341 
342  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
344  "Cannot open connexion with the motionblox");
345  }
346  return ;
347 }
348 
405 void
408 {
409 
410  InitTry;
411  // Read the robot constants from files
412  // - joint [min,max], coupl_56, long_56
413  // - camera extrinsic parameters relative to eMc
414  vpViper850::init(tool, projModel);
415 
416  // Set the camera constant (eMc pose) in the MotionBlox
417  double eMc_pose[6];
418  for (unsigned int i=0; i < 3; i ++) {
419  eMc_pose[i] = etc[i]; // translation in meters
420  eMc_pose[i+3] = erc[i]; // rotation in rad
421  }
422  // Update the eMc pose in the low level controller
423  Try( PrimitiveCONST_Viper850(eMc_pose) );
424 
425  // get real joint min/max from the MotionBlox
426  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
427  // Convert units from degrees to radians
428  joint_min.deg2rad();
429  joint_max.deg2rad();
430 
431  // for (unsigned int i=0; i < njoint; i++) {
432  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
433  // }
434 
435  setToolType(tool);
436 
437  CatchPrint();
438  return ;
439 }
440 
441 /* ------------------------------------------------------------------------ */
442 /* --- DESTRUCTOR --------------------------------------------------------- */
443 /* ------------------------------------------------------------------------ */
444 
452 {
453  InitTry;
454 
456 
457  // Look if the power is on or off
458  UInt32 HIPowerStatus;
459  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
460  &HIPowerStatus));
461  CAL_Wait(0.1);
462 
463  // if (HIPowerStatus == 1) {
464  // fprintf(stdout, "Power OFF the robot\n");
465  // fflush(stdout);
466 
467  // Try( PrimitivePOWEROFF_Viper850() );
468  // }
469 
470  // Free allocated resources
471  ShutDownConnection();
472 
473  vpRobotViper850::robotAlreadyCreated = false;
474 
475  CatchPrint();
476  return;
477 }
478 
479 
480 
481 
490 {
491  InitTry;
492 
493  switch (newState) {
494  case vpRobot::STATE_STOP: {
495  // Start primitive STOP only if the current state is Velocity
497  Try( PrimitiveSTOP_Viper850() );
498  }
499  break;
500  }
503  std::cout << "Change the control mode from velocity to position control.\n";
504  Try( PrimitiveSTOP_Viper850() );
505  }
506  else {
507  //std::cout << "Change the control mode from stop to position control.\n";
508  }
509  this->powerOn();
510  break;
511  }
514  std::cout << "Change the control mode from stop to velocity control.\n";
515  }
516  this->powerOn();
517  break;
518  }
519  default:
520  break ;
521  }
522 
523  CatchPrint();
524 
525  return vpRobot::setRobotState (newState);
526 }
527 
528 
529 /* ------------------------------------------------------------------------ */
530 /* --- STOP --------------------------------------------------------------- */
531 /* ------------------------------------------------------------------------ */
532 
540 void
542 {
544  return;
545 
546  InitTry;
547  Try( PrimitiveSTOP_Viper850() );
549 
550  CatchPrint();
551  if (TryStt < 0) {
552  vpERROR_TRACE ("Cannot stop robot motion");
554  "Cannot stop robot motion.");
555  }
556 }
557 
567 void
569 {
570  InitTry;
571 
572  // Look if the power is on or off
573  UInt32 HIPowerStatus;
574  UInt32 EStopStatus;
575  bool firsttime = true;
576  unsigned int nitermax = 10;
577 
578  for (unsigned int i=0; i<nitermax; i++) {
579  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
580  &HIPowerStatus));
581  if (EStopStatus == ESTOP_AUTO) {
582  controlMode = AUTO;
583  break; // exit for loop
584  }
585  else if (EStopStatus == ESTOP_MANUAL) {
586  controlMode = MANUAL;
587  break; // exit for loop
588  }
589  else if (EStopStatus == ESTOP_ACTIVATED) {
590  controlMode = ESTOP;
591  if (firsttime) {
592  std::cout << "Emergency stop is activated! \n"
593  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
594  firsttime = false;
595  }
596  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
597  fflush(stdout);
598  CAL_Wait(1);
599  }
600  else {
601  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
602  std::cout << "You have to call Adept for maintenance..." << std::endl;
603  // Free allocated resources
604  ShutDownConnection();
605  exit(0);
606  }
607  }
608 
609  if (EStopStatus == ESTOP_ACTIVATED)
610  std::cout << std::endl;
611 
612  if (EStopStatus == ESTOP_ACTIVATED) {
613  std::cout << "Sorry, cannot power on the robot." << std::endl;
615  "Cannot power on the robot.");
616  }
617 
618  if (HIPowerStatus == 0) {
619  fprintf(stdout, "Power ON the Viper850 robot\n");
620  fflush(stdout);
621 
622  Try( PrimitivePOWERON_Viper850() );
623  }
624 
625  CatchPrint();
626  if (TryStt < 0) {
627  vpERROR_TRACE ("Cannot power on the robot");
629  "Cannot power off the robot.");
630  }
631 }
632 
642 void
644 {
645  InitTry;
646 
647  // Look if the power is on or off
648  UInt32 HIPowerStatus;
649  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
650  &HIPowerStatus));
651  CAL_Wait(0.1);
652 
653  if (HIPowerStatus == 1) {
654  fprintf(stdout, "Power OFF the Viper850 robot\n");
655  fflush(stdout);
656 
657  Try( PrimitivePOWEROFF_Viper850() );
658  }
659 
660  CatchPrint();
661  if (TryStt < 0) {
662  vpERROR_TRACE ("Cannot power off the robot");
664  "Cannot power off the robot.");
665  }
666 }
667 
679 bool
681 {
682  InitTry;
683  bool status = false;
684  // Look if the power is on or off
685  UInt32 HIPowerStatus;
686  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
687  &HIPowerStatus));
688  CAL_Wait(0.1);
689 
690  if (HIPowerStatus == 1) {
691  status = true;
692  }
693 
694  CatchPrint();
695  if (TryStt < 0) {
696  vpERROR_TRACE ("Cannot get the power status");
698  "Cannot get the power status.");
699  }
700  return status;
701 }
702 
712 void
714 {
715  vpHomogeneousMatrix cMe ;
716  vpViper850::get_cMe(cMe) ;
717 
718  cVe.buildFrom(cMe) ;
719 }
720 
732 void
734 {
735  vpViper850::get_cMe(cMe) ;
736 }
737 
738 
750 void
752 {
753 
754  double position[6];
755  double timestamp;
756 
757  InitTry;
758  Try( PrimitiveACQ_POS_J_Viper850(position, &timestamp) );
759  CatchPrint();
760 
761  vpColVector q(6);
762  for (unsigned int i=0; i < njoint; i++)
763  q[i] = vpMath::rad(position[i]);
764 
765  try
766  {
767  vpViper850::get_eJe(q, eJe) ;
768  }
769  catch(...)
770  {
771  vpERROR_TRACE("catch exception ") ;
772  throw ;
773  }
774 }
787 void
789 {
790 
791  double position[6];
792  double timestamp;
793 
794  InitTry;
795  Try( PrimitiveACQ_POS_Viper850(position, &timestamp) );
796  CatchPrint();
797 
798  vpColVector q(6);
799  for (unsigned int i=0; i < njoint; i++)
800  q[i] = position[i];
801 
802  try
803  {
804  vpViper850::get_fJe(q, fJe) ;
805  }
806  catch(...)
807  {
808  vpERROR_TRACE("Error caught");
809  throw ;
810  }
811 }
812 
850 void
852 {
853  positioningVelocity = velocity;
854 }
855 
861 double
863 {
864  return positioningVelocity;
865 }
866 
867 
945 void
947  const vpColVector & position )
948 {
949 
951  {
952  vpERROR_TRACE ("Robot was not in position-based control\n"
953  "Modification of the robot state");
955  }
956 
957  vpColVector destination(njoint);
958  int error = 0;
959  double timestamp;
960 
961  InitTry;
962  switch(frame) {
963  case vpRobot::CAMERA_FRAME : {
964  vpColVector q(njoint);
965  Try( PrimitiveACQ_POS_Viper850(q.data, &timestamp) );
966 
967  // Convert degrees into rad
968  q.deg2rad();
969 
970  // Get fMc from the inverse kinematics
972  vpViper850::get_fMc(q, fMc);
973 
974  // Set cMc from the input position
975  vpTranslationVector txyz;
976  vpRxyzVector rxyz;
977  for (unsigned int i=0; i < 3; i++) {
978  txyz[i] = position[i];
979  rxyz[i] = position[i+3];
980  }
981 
982  // Compute cMc2
983  vpRotationMatrix cRc2(rxyz);
984  vpHomogeneousMatrix cMc2(txyz, cRc2);
985 
986  // Compute the new position to reach: fMc*cMc2
987  vpHomogeneousMatrix fMc2 = fMc * cMc2;
988 
989  // Compute the corresponding joint position from the inverse kinematics
990  unsigned int solution = this->getInverseKinematics(fMc2, q);
991  if (solution) { // Position is reachable
992  destination = q;
993  // convert rad to deg requested for the low level controller
994  destination.rad2deg();
995  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
996  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
997  }
998  else {
999  // Cartesian position is out of range
1000  error = -1;
1001  }
1002 
1003  break ;
1004  }
1005  case vpRobot::ARTICULAR_FRAME: {
1006  destination = position;
1007  // convert rad to deg requested for the low level controller
1008  destination.rad2deg();
1009 
1010  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1011  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
1012  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1013  break ;
1014 
1015  }
1016  case vpRobot::REFERENCE_FRAME: {
1017  // Convert angles from Rxyz representation to Rzyz representation
1018  vpRxyzVector rxyz(position[3],position[4],position[5]);
1019  vpRotationMatrix R(rxyz);
1020  vpRzyzVector rzyz(R);
1021 
1022  for (unsigned int i=0; i <3; i++) {
1023  destination[i] = position[i];
1024  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1025  }
1026  int configuration = 0; // keep the actual configuration
1027 
1028  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1029  Try( PrimitiveMOVE_C_Viper850(destination.data, configuration,
1030  positioningVelocity) );
1031  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1032 
1033  break ;
1034  }
1035  case vpRobot::MIXT_FRAME:
1036  {
1037  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1039  "Positionning error: "
1040  "Mixt frame not implemented.");
1041  break ;
1042  }
1043  }
1044 
1045  CatchPrint();
1046  if (TryStt == InvalidPosition || TryStt == -1023)
1047  std::cout << " : Position out of range.\n";
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 vpRobotViper850::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, double &timestamp)
1284 {
1285 
1286  InitTry;
1287 
1288  position.resize (6);
1289 
1290  switch (frame) {
1291  case vpRobot::CAMERA_FRAME : {
1292  position = 0;
1293  return;
1294  }
1295  case vpRobot::ARTICULAR_FRAME : {
1296  Try( PrimitiveACQ_POS_J_Viper850(position.data, &timestamp) );
1297  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1298  position.deg2rad();
1299 
1300  return;
1301  }
1302  case vpRobot::REFERENCE_FRAME : {
1303  Try( PrimitiveACQ_POS_C_Viper850(position.data, &timestamp) );
1304  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1305  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1306  // Convert Euler Rzyz angles from deg to rad
1307  for (unsigned int i=3; i <6; i++)
1308  position[i] = vpMath::rad(position[i]);
1309  // Convert Rzyz angles into Rxyz representation
1310  vpRzyzVector rzyz(position[3], position[4], position[5]);
1311  vpRotationMatrix R(rzyz);
1312  vpRxyzVector rxyz(R);
1313 
1314  // Update the position using Rxyz representation
1315  for (unsigned int i=0; i <3; i++)
1316  position[i+3] = rxyz[i];
1317  // vpCTRACE << "Cartesian position Rxyz (deg)"
1318  // << position[0] << " " << position[1] << " " << position[2] << " "
1319  // << vpMath::deg(position[3]) << " "
1320  // << vpMath::deg(position[4]) << " "
1321  // << vpMath::deg(position[5]) << std::endl;
1322 
1323  break ;
1324  }
1325  case vpRobot::MIXT_FRAME: {
1326  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1328  "Cannot get position in mixt frame: "
1329  "not implemented");
1330  break ;
1331  }
1332  }
1333 
1334  CatchPrint();
1335  if (TryStt < 0) {
1336  vpERROR_TRACE ("Cannot get position.");
1338  "Cannot get position.");
1339  }
1340 
1341  return;
1342 }
1343 
1348 {
1349  double timestamp;
1350  PrimitiveACQ_TIME_Viper850(&timestamp);
1351  return timestamp;
1352 }
1353 
1364  vpColVector & position)
1365 {
1366  double timestamp;
1367  getPosition(frame, position, timestamp);
1368 }
1369 
1381  vpPoseVector &position,
1382  double &timestamp)
1383 {
1384  vpColVector posRxyz;
1385  //recupere position en Rxyz
1386  this->getPosition(frame, posRxyz, timestamp);
1387  vpRxyzVector RxyzVect;
1388  for (unsigned int j=0;j<3;j++)
1389  RxyzVect[j]=posRxyz[j+3];
1390  //recupere le vecteur thetaU correspondant
1391  vpThetaUVector RtuVect(RxyzVect);
1392 
1393  //remplit le vpPoseVector avec translation et rotation ThetaU
1394  for (unsigned int j=0;j<3;j++)
1395  {
1396  position[j]=posRxyz[j];
1397  position[j+3]=RtuVect[j];
1398  }
1399 }
1400 
1411  vpPoseVector &position)
1412 {
1413  vpColVector posRxyz;
1414  double timestamp;
1415  //recupere position en Rxyz
1416  this->getPosition(frame, posRxyz, timestamp);
1417  vpRxyzVector RxyzVect;
1418  for (unsigned int j=0;j<3;j++)
1419  RxyzVect[j]=posRxyz[j+3];
1420  //recupere le vecteur thetaU correspondant
1421  vpThetaUVector RtuVect(RxyzVect);
1422 
1423  //remplit le vpPoseVector avec translation et rotation ThetaU
1424  for (unsigned int j=0;j<3;j++)
1425  {
1426  position[j]=posRxyz[j];
1427  position[j+3]=RtuVect[j];
1428  }
1429 }
1430 
1504  const vpColVector & vel)
1505 {
1507  vpERROR_TRACE ("Cannot send a velocity to the robot "
1508  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1510  "Cannot send a velocity to the robot "
1511  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1512  }
1513 
1514  vpColVector vel_sat(6);
1515 
1516  // Velocity saturation
1517  switch(frame) {
1518  // saturation in cartesian space
1519  case vpRobot::CAMERA_FRAME :
1521  case vpRobot::MIXT_FRAME : {
1522  vpColVector vel_max(6);
1523 
1524  for (unsigned int i=0; i<3; i++)
1525  vel_max[i] = getMaxTranslationVelocity();
1526  for (unsigned int i=3; i<6; i++)
1527  vel_max[i] = getMaxRotationVelocity();
1528 
1529  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1530 
1531  break;
1532  }
1533  // saturation in joint space
1534  case vpRobot::ARTICULAR_FRAME : {
1535  vpColVector vel_max(6);
1536 
1537  for (unsigned int i=0; i<6; i++)
1538  vel_max[i] = getMaxRotationVelocity();
1539 
1540  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1541  }
1542  }
1543 
1544  InitTry;
1545 
1546  switch(frame) {
1547  case vpRobot::CAMERA_FRAME : {
1548  // Send velocities in m/s and rad/s
1549  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1550  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPCAM_VIPER850) );
1551  break ;
1552  }
1553  case vpRobot::ARTICULAR_FRAME : {
1554  // Convert all the velocities from rad/s into deg/s
1555  vel_sat.rad2deg();
1556  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1557  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER850) );
1558  Try( PrimitiveMOVESPEED_Viper850(vel_sat.data) );
1559  break ;
1560  }
1561  case vpRobot::REFERENCE_FRAME : {
1562  // Send velocities in m/s and rad/s
1563  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1564  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPFIX_VIPER850) );
1565  break ;
1566  }
1567  case vpRobot::MIXT_FRAME : {
1568  //Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPMIX_VIPER850) );
1569  break ;
1570  }
1571  default: {
1572  vpERROR_TRACE ("Error in spec of vpRobot. "
1573  "Case not taken in account.");
1574  return;
1575  }
1576  }
1577 
1578  Catch();
1579  if (TryStt < 0) {
1580  if (TryStt == VelStopOnJoint) {
1581  UInt32 axisInJoint[njoint];
1582  PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1583  for (unsigned int i=0; i < njoint; i ++) {
1584  if (axisInJoint[i])
1585  std::cout << "\nWarning: Velocity control stopped: axis "
1586  << i+1 << " on joint limit!" <<std::endl;
1587  }
1588  }
1589  else {
1590  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1591  if (TryString != NULL) {
1592  // The statement is in TryString, but we need to check the validity
1593  printf(" Error sentence %s\n", TryString); // Print the TryString
1594  }
1595  else {
1596  printf("\n");
1597  }
1598  }
1599  }
1600 
1601  return;
1602 }
1603 
1604 
1605 
1606 
1607 
1608 
1609 /* ------------------------------------------------------------------------ */
1610 /* --- GET ---------------------------------------------------------------- */
1611 /* ------------------------------------------------------------------------ */
1612 
1613 
1671  vpColVector & velocity, double &timestamp)
1672 {
1673 
1674  velocity.resize (6);
1675  velocity = 0;
1676 
1677  vpColVector q_cur(6);
1678  vpHomogeneousMatrix fMc_cur;
1679  vpHomogeneousMatrix cMc; // camera displacement
1680  double time_cur;
1681 
1682  InitTry;
1683 
1684  // Get the current joint position
1685  Try( PrimitiveACQ_POS_J_Viper850(q_cur.data, &timestamp) );
1686  time_cur = timestamp;
1687  q_cur.deg2rad();
1688 
1689  // Get the camera pose from the direct kinematics
1690  vpViper850::get_fMc(q_cur, fMc_cur);
1691 
1692  if ( ! first_time_getvel ) {
1693 
1694  switch (frame) {
1695  case vpRobot::CAMERA_FRAME: {
1696  // Compute the displacement of the camera since the previous call
1697  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1698 
1699  // Compute the velocity of the camera from this displacement
1700  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1701 
1702  break ;
1703  }
1704 
1705  case vpRobot::ARTICULAR_FRAME: {
1706  velocity = (q_cur - q_prev_getvel)
1707  / (time_cur - time_prev_getvel);
1708  break ;
1709  }
1710 
1711  case vpRobot::REFERENCE_FRAME: {
1712  // Compute the displacement of the camera since the previous call
1713  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1714 
1715  // Compute the velocity of the camera from this displacement
1716  vpColVector v;
1717  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1718 
1719  // Express this velocity in the reference frame
1720  vpVelocityTwistMatrix fVc(fMc_cur);
1721  velocity = fVc * v;
1722 
1723  break ;
1724  }
1725 
1726  case vpRobot::MIXT_FRAME: {
1727  // Compute the displacement of the camera since the previous call
1728  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1729 
1730  // Compute the ThetaU representation for the rotation
1731  vpRotationMatrix cRc;
1732  cMc.extract(cRc);
1733  vpThetaUVector thetaU;
1734  thetaU.buildFrom(cRc);
1735 
1736  for (unsigned int i=0; i < 3; i++) {
1737  // Compute the translation displacement in the reference frame
1738  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1739  // Update the rotation displacement in the camera frame
1740  velocity[i+3] = thetaU[i];
1741  }
1742 
1743  // Compute the velocity
1744  velocity /= (time_cur - time_prev_getvel);
1745  break ;
1746  }
1747  }
1748  }
1749  else {
1750  first_time_getvel = false;
1751  }
1752 
1753  // Memorize the camera pose for the next call
1754  fMc_prev_getvel = fMc_cur;
1755 
1756  // Memorize the joint position for the next call
1757  q_prev_getvel = q_cur;
1758 
1759  // Memorize the time associated to the joint position for the next call
1760  time_prev_getvel = time_cur;
1761 
1762 
1763  CatchPrint();
1764  if (TryStt < 0) {
1765  vpERROR_TRACE ("Cannot get velocity.");
1767  "Cannot get velocity.");
1768  }
1769 }
1770 
1780  vpColVector & velocity)
1781 {
1782  double timestamp;
1783  getVelocity(frame, velocity, timestamp);
1784 }
1785 
1837 {
1838  vpColVector velocity;
1839  getVelocity (frame, velocity, timestamp);
1840 
1841  return velocity;
1842 }
1843 
1853 {
1854  vpColVector velocity;
1855  double timestamp;
1856  getVelocity (frame, velocity, timestamp);
1857 
1858  return velocity;
1859 }
1860 
1926 bool
1927  vpRobotViper850::readPosFile(const char *filename, vpColVector &q)
1928 {
1929 
1930  FILE * fd ;
1931  fd = fopen(filename, "r") ;
1932  if (fd == NULL)
1933  return false;
1934 
1935  char line[FILENAME_MAX];
1936  char dummy[FILENAME_MAX];
1937  char head[] = "R:";
1938  bool sortie = false;
1939 
1940  do {
1941  // Saut des lignes commencant par #
1942  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1943  if ( strncmp (line, "#", 1) != 0) {
1944  // La ligne n'est pas un commentaire
1945  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1946  sortie = true; // Position robot trouvee.
1947  }
1948  // else
1949  // return (false); // fin fichier sans position robot.
1950  }
1951  }
1952  else {
1953  return (false); /* fin fichier */
1954  }
1955 
1956  }
1957  while ( sortie != true );
1958 
1959  // Lecture des positions
1960  q.resize(njoint);
1961  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1962  dummy,
1963  &q[0], &q[1], &q[2],
1964  &q[3], &q[4], &q[5]);
1965 
1966  // converts rotations from degrees into radians
1967  q.deg2rad();
1968 
1969  fclose(fd) ;
1970  return (true);
1971 }
1972 
1996 bool
1997  vpRobotViper850::savePosFile(const char *filename, const vpColVector &q)
1998 {
1999 
2000  FILE * fd ;
2001  fd = fopen(filename, "w") ;
2002  if (fd == NULL)
2003  return false;
2004 
2005  fprintf(fd, "\
2006 #Viper - Position - Version 1.0\n\
2007 #\n\
2008 # R: A B C D E F\n\
2009 # Joint position in degrees\n\
2010 #\n\
2011 #\n\n");
2012 
2013  // Save positions in mm and deg
2014  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2015  vpMath::deg(q[0]),
2016  vpMath::deg(q[1]),
2017  vpMath::deg(q[2]),
2018  vpMath::deg(q[3]),
2019  vpMath::deg(q[4]),
2020  vpMath::deg(q[5]));
2021 
2022  fclose(fd) ;
2023  return (true);
2024 }
2025 
2036 void
2037  vpRobotViper850::move(const char *filename)
2038 {
2039  vpColVector q;
2040 
2041  try {
2042  this->readPosFile(filename, q) ;
2044  this->setPositioningVelocity(10);
2046  }
2047  catch(...) {
2048  throw;
2049  }
2050 }
2051 
2065 void
2066  vpRobotViper850::getCameraDisplacement(vpColVector &displacement)
2067 {
2068  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2069 }
2081 void
2082  vpRobotViper850::getArticularDisplacement(vpColVector &displacement)
2083 {
2085 }
2086 
2107 void
2109  vpColVector &displacement)
2110 {
2111  displacement.resize (6);
2112  displacement = 0;
2113 
2114  double q[6];
2115  vpColVector q_cur(6);
2116  double timestamp;
2117 
2118  InitTry;
2119 
2120  // Get the current joint position
2121  Try( PrimitiveACQ_POS_Viper850(q, &timestamp) );
2122  for (unsigned int i=0; i < njoint; i ++) {
2123  q_cur[i] = q[i];
2124  }
2125 
2126  if ( ! first_time_getdis ) {
2127  switch (frame) {
2128  case vpRobot::CAMERA_FRAME: {
2129  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2130  return;
2131  break ;
2132  }
2133 
2134  case vpRobot::ARTICULAR_FRAME: {
2135  displacement = q_cur - q_prev_getdis;
2136  break ;
2137  }
2138 
2139  case vpRobot::REFERENCE_FRAME: {
2140  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2141  return;
2142  break ;
2143  }
2144 
2145  case vpRobot::MIXT_FRAME: {
2146  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2147  return;
2148  break ;
2149  }
2150  }
2151  }
2152  else {
2153  first_time_getdis = false;
2154  }
2155 
2156  // Memorize the joint position for the next call
2157  q_prev_getdis = q_cur;
2158 
2159  CatchPrint();
2160  if (TryStt < 0) {
2161  vpERROR_TRACE ("Cannot get velocity.");
2163  "Cannot get velocity.");
2164  }
2165 }
2166 
2180 void
2182 {
2183  InitTry;
2184 
2185  Try( PrimitiveTFS_BIAS_Viper850() );
2186 
2187  // Wait 500 ms to be sure the next measures take into account the bias
2188  vpTime::wait(500);
2189 
2190  CatchPrint();
2191  if (TryStt < 0) {
2192  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2194  "Cannot bias the force/torque sensor.");
2195  }
2196 }
2197 
2237 void
2239 {
2240  InitTry;
2241 
2242  H.resize (6);
2243 
2244  Try( PrimitiveTFS_ACQ_Viper850(H.data) );
2245 
2246  CatchPrint();
2247  if (TryStt < 0) {
2248  vpERROR_TRACE ("Cannot get the force/torque measures.");
2250  "Cannot get force/torque measures.");
2251  }
2252 }
2259 void
2261 {
2262  InitTry;
2263  Try( PrimitiveGripper_Viper850(1) );
2264  std::cout << "Open the gripper..." << std::endl;
2265  CatchPrint();
2266  if (TryStt < 0) {
2267  vpERROR_TRACE ("Cannot open the gripper");
2269  "Cannot open the gripper.");
2270  }
2271 }
2272 
2281 {
2282  InitTry;
2283  Try( PrimitiveGripper_Viper850(0) );
2284  std::cout << "Close the gripper..." << std::endl;
2285  CatchPrint();
2286  if (TryStt < 0) {
2287  vpERROR_TRACE ("Cannot close the gripper");
2289  "Cannot close the gripper.");
2290  }
2291 }
2292 
2293 
2294 #endif
2295 
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
static vpColVector inverse(const vpHomogeneousMatrix &M)
Definition of the vpMatrix class.
Definition: vpMatrix.h:96
double getPositioningVelocity(void)
Error that can be emited by the vpRobot class and its derivates.
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:99
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
virtual vpRobotStateType getRobotState(void)
Definition: vpRobot.h:139
void setPositioningVelocity(const double velocity)
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:203
Initialize the position controller.
Definition: vpRobot.h:71
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
class that defines a generic virtual robot
Definition: vpRobot.h:60
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 get_eJe(vpMatrix &eJe)
static int wait(double t0, double t)
Definition: vpTime.cpp:149
static bool savePosFile(const char *filename, const vpColVector &q)
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
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q)
Definition: vpViper.cpp:559
The vpRotationMatrix considers the particular case of a rotation matrix.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
double * data
address of the first element of the data array
Definition: vpMatrix.h:116
static bool readPosFile(const char *filename, vpColVector &q)
Initialize the velocity controller.
Definition: vpRobot.h:70
vpRobotStateType
Definition: vpRobot.h:66
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
Definition: vpViper850.h:136
bool verbose_
Definition: vpRobot.h:115
vpTranslationVector etc
Definition: vpViper.h:149
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void getForceTorque(vpColVector &H)
vpRowVector t() const
transpose of Vector
vpColVector joint_max
Definition: vpViper.h:161
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:91
Modelisation of the ADEPT Viper 850 robot.
Definition: vpViper850.h:66
void extract(vpRotationMatrix &R) const
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
void get_fJe(vpMatrix &fJe)
static double rad(double deg)
Definition: vpMath.h:100
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpViper.cpp:1160
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
static double deg(double rad)
Definition: vpMath.h:93
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
Manual control mode activated when the dead man switch is in use.
static const double defaultPositioningVelocity
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
void get_cVe(vpVelocityTwistMatrix &cVe)
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
Emergency stop activated.
Class that consider the case of the Euler angles using the z-y-z convention, where are respectively...
Definition: vpRzyzVector.h:150
virtual ~vpRobotViper850(void)
void init(void)
Definition: vpViper850.cpp:174
Automatic control mode (default).
double getTime() const
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
void move(const char *filename)
void get_cMe(vpHomogeneousMatrix &cMe)
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:597
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:94
vpColVector joint_min
Definition: vpViper.h:162