Visual Servoing Platform  version 3.0.0
vpRobotViper850.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Interface for the Irisa's Viper S850 robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #include <visp3/core/vpConfig.h>
39 
40 #ifdef VISP_HAVE_VIPER850
41 
42 #include <signal.h>
43 #include <stdlib.h>
44 #include <sys/types.h>
45 #include <unistd.h>
46 
47 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpExponentialMap.h>
49 #include <visp3/core/vpDebug.h>
50 #include <visp3/core/vpVelocityTwistMatrix.h>
51 #include <visp3/core/vpThetaUVector.h>
52 #include <visp3/robot/vpRobot.h>
53 #include <visp3/robot/vpRobotViper850.h>
54 
55 /* ---------------------------------------------------------------------- */
56 /* --- STATIC ----------------------------------------------------------- */
57 /* ---------------------------------------------------------------------- */
58 
59 bool vpRobotViper850::robotAlreadyCreated = false;
60 
69 
70 /* ---------------------------------------------------------------------- */
71 /* --- EMERGENCY STOP --------------------------------------------------- */
72 /* ---------------------------------------------------------------------- */
73 
81 void emergencyStopViper850(int signo)
82 {
83  std::cout << "Stop the Viper850 application by signal ("
84  << signo << "): " << (char)7 ;
85  switch(signo)
86  {
87  case SIGINT:
88  std::cout << "SIGINT (stop by ^C) " << std::endl ; break ;
89  case SIGBUS:
90  std::cout <<"SIGBUS (stop due to a bus error) " << std::endl ; break ;
91  case SIGSEGV:
92  std::cout <<"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
93  case SIGKILL:
94  std::cout <<"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
95  case SIGQUIT:
96  std::cout <<"SIGQUIT " << std::endl ; break ;
97  default :
98  std::cout << signo << std::endl ;
99 }
100  //std::cout << "Emergency stop called\n";
101  // PrimitiveESTOP_Viper850();
102  PrimitiveSTOP_Viper850();
103  std::cout << "Robot was stopped\n";
104 
105  // Free allocated resources
106  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
107 
108  fprintf(stdout, "Application ");
109  fflush(stdout);
110  kill(getpid(), SIGKILL);
111  exit(1) ;
112 }
113 
114 /* ---------------------------------------------------------------------- */
115 /* --- CONSTRUCTOR ------------------------------------------------------ */
116 /* ---------------------------------------------------------------------- */
117 
173 vpRobotViper850::vpRobotViper850 (bool verbose)
174  :
175  vpViper850 (),
176  vpRobot ()
177 {
178 
179  /*
180  #define SIGHUP 1 // hangup
181  #define SIGINT 2 // interrupt (rubout)
182  #define SIGQUIT 3 // quit (ASCII FS)
183  #define SIGILL 4 // illegal instruction (not reset when caught)
184  #define SIGTRAP 5 // trace trap (not reset when caught)
185  #define SIGIOT 6 // IOT instruction
186  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
187  #define SIGEMT 7 // EMT instruction
188  #define SIGFPE 8 // floating point exception
189  #define SIGKILL 9 // kill (cannot be caught or ignored)
190  #define SIGBUS 10 // bus error
191  #define SIGSEGV 11 // segmentation violation
192  #define SIGSYS 12 // bad argument to system call
193  #define SIGPIPE 13 // write on a pipe with no one to read it
194  #define SIGALRM 14 // alarm clock
195  #define SIGTERM 15 // software termination signal from kill
196  */
197 
198  signal(SIGINT, emergencyStopViper850);
199  signal(SIGBUS, emergencyStopViper850) ;
200  signal(SIGSEGV, emergencyStopViper850) ;
201  signal(SIGKILL, emergencyStopViper850);
202  signal(SIGQUIT, emergencyStopViper850);
203 
204  setVerbose(verbose);
205  if (verbose_)
206  std::cout << "Open communication with MotionBlox.\n";
207  try {
208  this->init();
210  }
211  catch(...) {
212  // vpERROR_TRACE("Error caught") ;
213  throw ;
214  }
215  positioningVelocity = defaultPositioningVelocity ;
216 
217  maxRotationVelocity_joint6 = maxRotationVelocity;
218 
219  vpRobotViper850::robotAlreadyCreated = true;
220 
221  return ;
222 }
223 
224 
225 /* ------------------------------------------------------------------------ */
226 /* --- INITIALISATION ----------------------------------------------------- */
227 /* ------------------------------------------------------------------------ */
228 
248 void
250 {
251  InitTry;
252 
253  // Initialise private variables used to compute the measured velocities
254  q_prev_getvel.resize(6);
255  q_prev_getvel = 0;
256  time_prev_getvel = 0;
257  first_time_getvel = true;
258 
259  // Initialise private variables used to compute the measured displacement
260  q_prev_getdis.resize(6);
261  q_prev_getdis = 0;
262  first_time_getdis = true;
263 
264 
265  // Initialize the firewire connection
266  Try( InitializeConnection(verbose_) );
267 
268  // Connect to the servoboard using the servo board GUID
269  Try( InitializeNode_Viper850() );
270 
271  Try( PrimitiveRESET_Viper850() );
272 
273  // Enable the joint limits on axis 6
274  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
275 
276  // Update the eMc matrix in the low level controller
278 
279  // Look if the power is on or off
280  UInt32 HIPowerStatus;
281  UInt32 EStopStatus;
282  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
283  &HIPowerStatus));
284  CAL_Wait(0.1);
285 
286  // Print the robot status
287  if (verbose_) {
288  std::cout << "Robot status: ";
289  switch(EStopStatus) {
290  case ESTOP_AUTO:
291  controlMode = AUTO;
292  if (HIPowerStatus == 0)
293  std::cout << "Power is OFF" << std::endl;
294  else
295  std::cout << "Power is ON" << std::endl;
296  break;
297 
298  case ESTOP_MANUAL:
299  controlMode = MANUAL;
300  if (HIPowerStatus == 0)
301  std::cout << "Power is OFF" << std::endl;
302  else
303  std::cout << "Power is ON" << std::endl;
304  break;
305  case ESTOP_ACTIVATED:
306  controlMode = ESTOP;
307  std::cout << "Emergency stop is activated" << std::endl;
308  break;
309  default:
310  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
311  std::cout << "You have to call Adept for maintenance..." << std::endl;
312  // Free allocated resources
313  }
314  std::cout << std::endl;
315  }
316  // get real joint min/max from the MotionBlox
317  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
318  // Convert units from degrees to radians
319  joint_min.deg2rad();
320  joint_max.deg2rad();
321 
322  // for (unsigned int i=0; i < njoint; i++) {
323  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
324  // }
325 
326  // If an error occur in the low level controller, goto here
327  //CatchPrint();
328  Catch();
329 
330  // Test if an error occurs
331  if (TryStt == -20001)
332  printf("No connection detected. Check if the robot is powered on \n"
333  "and if the firewire link exist between the MotionBlox and this computer.\n");
334  else if (TryStt == -675)
335  printf(" Timeout enabling power...\n");
336 
337  if (TryStt < 0) {
338  // Power off the robot
339  PrimitivePOWEROFF_Viper850();
340  // Free allocated resources
341  ShutDownConnection();
342 
343  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
345  "Cannot open connexion with the motionblox");
346  }
347  return ;
348 }
349 
406 void
409 {
410 
411  InitTry;
412  // Read the robot constants from files
413  // - joint [min,max], coupl_56, long_56
414  // - camera extrinsic parameters relative to eMc
415  vpViper850::init(tool, projModel);
416 
417  // Set the camera constant (eMc pose) in the MotionBlox
418  double eMc_pose[6];
419  for (unsigned int i=0; i < 3; i ++) {
420  eMc_pose[i] = etc[i]; // translation in meters
421  eMc_pose[i+3] = erc[i]; // rotation in rad
422  }
423  // Update the eMc pose in the low level controller
424  Try( PrimitiveCONST_Viper850(eMc_pose) );
425 
426  // get real joint min/max from the MotionBlox
427  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
428  // Convert units from degrees to radians
429  joint_min.deg2rad();
430  joint_max.deg2rad();
431 
432  // for (unsigned int i=0; i < njoint; i++) {
433  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
434  // }
435 
436  setToolType(tool);
437 
438  CatchPrint();
439  return ;
440 }
441 
442 /* ------------------------------------------------------------------------ */
443 /* --- DESTRUCTOR --------------------------------------------------------- */
444 /* ------------------------------------------------------------------------ */
445 
453 {
454  InitTry;
455 
457 
458  // Look if the power is on or off
459  UInt32 HIPowerStatus;
460  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
461  &HIPowerStatus));
462  CAL_Wait(0.1);
463 
464  // if (HIPowerStatus == 1) {
465  // fprintf(stdout, "Power OFF the robot\n");
466  // fflush(stdout);
467 
468  // Try( PrimitivePOWEROFF_Viper850() );
469  // }
470 
471  // Free allocated resources
472  ShutDownConnection();
473 
474  vpRobotViper850::robotAlreadyCreated = false;
475 
476  CatchPrint();
477  return;
478 }
479 
480 
481 
482 
491 {
492  InitTry;
493 
494  switch (newState) {
495  case vpRobot::STATE_STOP: {
496  // Start primitive STOP only if the current state is Velocity
498  Try( PrimitiveSTOP_Viper850() );
499  }
500  break;
501  }
504  std::cout << "Change the control mode from velocity to position control.\n";
505  Try( PrimitiveSTOP_Viper850() );
506  }
507  else {
508  //std::cout << "Change the control mode from stop to position control.\n";
509  }
510  this->powerOn();
511  break;
512  }
515  std::cout << "Change the control mode from stop to velocity control.\n";
516  }
517  this->powerOn();
518  break;
519  }
520  default:
521  break ;
522  }
523 
524  CatchPrint();
525 
526  return vpRobot::setRobotState (newState);
527 }
528 
529 
530 /* ------------------------------------------------------------------------ */
531 /* --- STOP --------------------------------------------------------------- */
532 /* ------------------------------------------------------------------------ */
533 
541 void
543 {
545  return;
546 
547  InitTry;
548  Try( PrimitiveSTOP_Viper850() );
550 
551  CatchPrint();
552  if (TryStt < 0) {
553  vpERROR_TRACE ("Cannot stop robot motion");
555  "Cannot stop robot motion.");
556  }
557 }
558 
568 void
570 {
571  InitTry;
572 
573  // Look if the power is on or off
574  UInt32 HIPowerStatus;
575  UInt32 EStopStatus;
576  bool firsttime = true;
577  unsigned int nitermax = 10;
578 
579  for (unsigned int i=0; i<nitermax; i++) {
580  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
581  &HIPowerStatus));
582  if (EStopStatus == ESTOP_AUTO) {
583  controlMode = AUTO;
584  break; // exit for loop
585  }
586  else if (EStopStatus == ESTOP_MANUAL) {
587  controlMode = MANUAL;
588  break; // exit for loop
589  }
590  else if (EStopStatus == ESTOP_ACTIVATED) {
591  controlMode = ESTOP;
592  if (firsttime) {
593  std::cout << "Emergency stop is activated! \n"
594  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
595  firsttime = false;
596  }
597  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
598  fflush(stdout);
599  CAL_Wait(1);
600  }
601  else {
602  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
603  std::cout << "You have to call Adept for maintenance..." << std::endl;
604  // Free allocated resources
605  ShutDownConnection();
606  exit(0);
607  }
608  }
609 
610  if (EStopStatus == ESTOP_ACTIVATED)
611  std::cout << std::endl;
612 
613  if (EStopStatus == ESTOP_ACTIVATED) {
614  std::cout << "Sorry, cannot power on the robot." << std::endl;
616  "Cannot power on the robot.");
617  }
618 
619  if (HIPowerStatus == 0) {
620  fprintf(stdout, "Power ON the Viper850 robot\n");
621  fflush(stdout);
622 
623  Try( PrimitivePOWERON_Viper850() );
624  }
625 
626  CatchPrint();
627  if (TryStt < 0) {
628  vpERROR_TRACE ("Cannot power on the robot");
630  "Cannot power off the robot.");
631  }
632 }
633 
643 void
645 {
646  InitTry;
647 
648  // Look if the power is on or off
649  UInt32 HIPowerStatus;
650  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
651  &HIPowerStatus));
652  CAL_Wait(0.1);
653 
654  if (HIPowerStatus == 1) {
655  fprintf(stdout, "Power OFF the Viper850 robot\n");
656  fflush(stdout);
657 
658  Try( PrimitivePOWEROFF_Viper850() );
659  }
660 
661  CatchPrint();
662  if (TryStt < 0) {
663  vpERROR_TRACE ("Cannot power off the robot");
665  "Cannot power off the robot.");
666  }
667 }
668 
680 bool
682 {
683  InitTry;
684  bool status = false;
685  // Look if the power is on or off
686  UInt32 HIPowerStatus;
687  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
688  &HIPowerStatus));
689  CAL_Wait(0.1);
690 
691  if (HIPowerStatus == 1) {
692  status = true;
693  }
694 
695  CatchPrint();
696  if (TryStt < 0) {
697  vpERROR_TRACE ("Cannot get the power status");
699  "Cannot get the power status.");
700  }
701  return status;
702 }
703 
713 void
715 {
716  vpHomogeneousMatrix cMe ;
717  vpViper850::get_cMe(cMe) ;
718 
719  cVe.buildFrom(cMe) ;
720 }
721 
733 void
735 {
736  vpViper850::get_cMe(cMe) ;
737 }
738 
739 
751 void
753 {
754 
755  double position[6];
756  double timestamp;
757 
758  InitTry;
759  Try( PrimitiveACQ_POS_J_Viper850(position, &timestamp) );
760  CatchPrint();
761 
762  vpColVector q(6);
763  for (unsigned int i=0; i < njoint; i++)
764  q[i] = vpMath::rad(position[i]);
765 
766  try
767  {
768  vpViper850::get_eJe(q, eJe) ;
769  }
770  catch(...)
771  {
772  vpERROR_TRACE("catch exception ") ;
773  throw ;
774  }
775 }
788 void
790 {
791 
792  double position[6];
793  double timestamp;
794 
795  InitTry;
796  Try( PrimitiveACQ_POS_Viper850(position, &timestamp) );
797  CatchPrint();
798 
799  vpColVector q(6);
800  for (unsigned int i=0; i < njoint; i++)
801  q[i] = position[i];
802 
803  try
804  {
805  vpViper850::get_fJe(q, fJe) ;
806  }
807  catch(...)
808  {
809  vpERROR_TRACE("Error caught");
810  throw ;
811  }
812 }
813 
851 void
853 {
854  positioningVelocity = velocity;
855 }
856 
862 double
864 {
865  return positioningVelocity;
866 }
867 
868 
946 void
948  const vpColVector & position )
949 {
950 
952  {
953  vpERROR_TRACE ("Robot was not in position-based control\n"
954  "Modification of the robot state");
956  }
957 
958  vpColVector destination(njoint);
959  int error = 0;
960  double timestamp;
961 
962  InitTry;
963  switch(frame) {
964  case vpRobot::CAMERA_FRAME : {
965  vpColVector q(njoint);
966  Try( PrimitiveACQ_POS_Viper850(q.data, &timestamp) );
967 
968  // Convert degrees into rad
969  q.deg2rad();
970 
971  // Get fMc from the inverse kinematics
973  vpViper850::get_fMc(q, fMc);
974 
975  // Set cMc from the input position
976  vpTranslationVector txyz;
977  vpRxyzVector rxyz;
978  for (unsigned int i=0; i < 3; i++) {
979  txyz[i] = position[i];
980  rxyz[i] = position[i+3];
981  }
982 
983  // Compute cMc2
984  vpRotationMatrix cRc2(rxyz);
985  vpHomogeneousMatrix cMc2(txyz, cRc2);
986 
987  // Compute the new position to reach: fMc*cMc2
988  vpHomogeneousMatrix fMc2 = fMc * cMc2;
989 
990  // Compute the corresponding joint position from the inverse kinematics
991  unsigned int solution = this->getInverseKinematics(fMc2, q);
992  if (solution) { // Position is reachable
993  destination = q;
994  // convert rad to deg requested for the low level controller
995  destination.rad2deg();
996  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
997  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
998  }
999  else {
1000  // Cartesian position is out of range
1001  error = -1;
1002  }
1003 
1004  break ;
1005  }
1006  case vpRobot::ARTICULAR_FRAME: {
1007  destination = position;
1008  // convert rad to deg requested for the low level controller
1009  destination.rad2deg();
1010 
1011  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1012  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
1013  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1014  break ;
1015 
1016  }
1017  case vpRobot::REFERENCE_FRAME: {
1018  // Convert angles from Rxyz representation to Rzyz representation
1019  vpRxyzVector rxyz(position[3],position[4],position[5]);
1020  vpRotationMatrix R(rxyz);
1021  vpRzyzVector rzyz(R);
1022 
1023  for (unsigned int i=0; i <3; i++) {
1024  destination[i] = position[i];
1025  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1026  }
1027  int configuration = 0; // keep the actual configuration
1028 
1029  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1030  Try( PrimitiveMOVE_C_Viper850(destination.data, configuration,
1031  positioningVelocity) );
1032  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1033 
1034  break ;
1035  }
1036  case vpRobot::MIXT_FRAME:
1037  {
1038  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1040  "Positionning error: "
1041  "Mixt frame not implemented.");
1042  break ;
1043  }
1044  }
1045 
1046  CatchPrint();
1047  if (TryStt == InvalidPosition || TryStt == -1023)
1048  std::cout << " : Position out of range.\n";
1049  else if (TryStt == -3019) {
1050  if (frame == vpRobot::ARTICULAR_FRAME)
1051  std::cout << " : Joint position out of range.\n";
1052  else
1053  std::cout << " : Cartesian position leads to a joint position out of range.\n";
1054  }
1055  else if (TryStt < 0)
1056  std::cout << " : Unknown error (see Fabien).\n";
1057  else if (error == -1)
1058  std::cout << "Position out of range.\n";
1059 
1060  if (TryStt < 0 || error < 0) {
1061  vpERROR_TRACE ("Positionning error.");
1063  "Position out of range.");
1064  }
1065 
1066  return ;
1067 }
1068 
1135  const double pos1,
1136  const double pos2,
1137  const double pos3,
1138  const double pos4,
1139  const double pos5,
1140  const double pos6)
1141 {
1142  try{
1143  vpColVector position(6) ;
1144  position[0] = pos1 ;
1145  position[1] = pos2 ;
1146  position[2] = pos3 ;
1147  position[3] = pos4 ;
1148  position[4] = pos5 ;
1149  position[5] = pos6 ;
1150 
1151  setPosition(frame, position) ;
1152  }
1153  catch(...)
1154  {
1155  vpERROR_TRACE("Error caught");
1156  throw ;
1157  }
1158 }
1159 
1199 void vpRobotViper850::setPosition(const char *filename)
1200 {
1201  vpColVector q;
1202  bool ret;
1203 
1204  ret = this->readPosFile(filename, q);
1205 
1206  if (ret == false) {
1207  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1209  "Bad position in filename.");
1210  }
1213 }
1214 
1284  vpColVector & position, 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_Viper850(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_Viper850(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 
1349 {
1350  double timestamp;
1351  PrimitiveACQ_TIME_Viper850(&timestamp);
1352  return timestamp;
1353 }
1354 
1365  vpColVector & position)
1366 {
1367  double timestamp;
1368  getPosition(frame, position, timestamp);
1369 }
1370 
1382  vpPoseVector &position,
1383  double &timestamp)
1384 {
1385  vpColVector posRxyz;
1386  //recupere position en Rxyz
1387  this->getPosition(frame, posRxyz, timestamp);
1388  vpRxyzVector RxyzVect;
1389  for (unsigned int j=0;j<3;j++)
1390  RxyzVect[j]=posRxyz[j+3];
1391  //recupere le vecteur thetaU correspondant
1392  vpThetaUVector RtuVect(RxyzVect);
1393 
1394  //remplit le vpPoseVector avec translation et rotation ThetaU
1395  for (unsigned int j=0;j<3;j++)
1396  {
1397  position[j]=posRxyz[j];
1398  position[j+3]=RtuVect[j];
1399  }
1400 }
1401 
1412  vpPoseVector &position)
1413 {
1414  vpColVector posRxyz;
1415  double timestamp;
1416  //recupere position en Rxyz
1417  this->getPosition(frame, posRxyz, timestamp);
1418  vpRxyzVector RxyzVect;
1419  for (unsigned int j=0;j<3;j++)
1420  RxyzVect[j]=posRxyz[j+3];
1421  //recupere le vecteur thetaU correspondant
1422  vpThetaUVector RtuVect(RxyzVect);
1423 
1424  //remplit le vpPoseVector avec translation et rotation ThetaU
1425  for (unsigned int j=0;j<3;j++)
1426  {
1427  position[j]=posRxyz[j];
1428  position[j+3]=RtuVect[j];
1429  }
1430 }
1431 
1505  const vpColVector & vel)
1506 {
1508  vpERROR_TRACE ("Cannot send a velocity to the robot "
1509  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1511  "Cannot send a velocity to the robot "
1512  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1513  }
1514 
1515  vpColVector vel_sat(6);
1516 
1517  // Velocity saturation
1518  switch(frame) {
1519  // saturation in cartesian space
1520  case vpRobot::CAMERA_FRAME :
1522  case vpRobot::MIXT_FRAME : {
1523  vpColVector vel_max(6);
1524 
1525  for (unsigned int i=0; i<3; i++)
1526  vel_max[i] = getMaxTranslationVelocity();
1527  for (unsigned int i=3; i<6; i++)
1528  vel_max[i] = getMaxRotationVelocity();
1529 
1530  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1531 
1532  break;
1533  }
1534  // saturation in joint space
1535  case vpRobot::ARTICULAR_FRAME : {
1536  vpColVector vel_max(6);
1537 
1539  for (unsigned int i=0; i<6; i++)
1540  vel_max[i] = getMaxRotationVelocity();
1541  }
1542  else {
1543  for (unsigned int i=0; i<5; i++)
1544  vel_max[i] = getMaxRotationVelocity();
1545  vel_max[5] = getMaxRotationVelocityJoint6();
1546  }
1547 
1548  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1549  }
1550  }
1551 
1552  InitTry;
1553 
1554  switch(frame) {
1555  case vpRobot::CAMERA_FRAME : {
1556  // Send velocities in m/s and rad/s
1557  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1558  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPCAM_VIPER850) );
1559  break ;
1560  }
1561  case vpRobot::ARTICULAR_FRAME : {
1562  // Convert all the velocities from rad/s into deg/s
1563  vel_sat.rad2deg();
1564  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1565  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER850) );
1566  Try( PrimitiveMOVESPEED_Viper850(vel_sat.data) );
1567  break ;
1568  }
1569  case vpRobot::REFERENCE_FRAME : {
1570  // Send velocities in m/s and rad/s
1571  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1572  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPFIX_VIPER850) );
1573  break ;
1574  }
1575  case vpRobot::MIXT_FRAME : {
1576  //Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPMIX_VIPER850) );
1577  break ;
1578  }
1579  default: {
1580  vpERROR_TRACE ("Error in spec of vpRobot. "
1581  "Case not taken in account.");
1582  return;
1583  }
1584  }
1585 
1586  Catch();
1587  if (TryStt < 0) {
1588  if (TryStt == VelStopOnJoint) {
1589  UInt32 axisInJoint[njoint];
1590  PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1591  for (unsigned int i=0; i < njoint; i ++) {
1592  if (axisInJoint[i])
1593  std::cout << "\nWarning: Velocity control stopped: axis "
1594  << i+1 << " on joint limit!" <<std::endl;
1595  }
1596  }
1597  else {
1598  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1599  if (TryString != NULL) {
1600  // The statement is in TryString, but we need to check the validity
1601  printf(" Error sentence %s\n", TryString); // Print the TryString
1602  }
1603  else {
1604  printf("\n");
1605  }
1606  }
1607  }
1608 
1609  return;
1610 }
1611 
1612 
1613 
1614 
1615 
1616 
1617 /* ------------------------------------------------------------------------ */
1618 /* --- GET ---------------------------------------------------------------- */
1619 /* ------------------------------------------------------------------------ */
1620 
1621 
1679  vpColVector & velocity, double &timestamp)
1680 {
1681 
1682  velocity.resize (6);
1683  velocity = 0;
1684 
1685  vpColVector q_cur(6);
1686  vpHomogeneousMatrix fMc_cur;
1687  vpHomogeneousMatrix cMc; // camera displacement
1688  double time_cur;
1689 
1690  InitTry;
1691 
1692  // Get the current joint position
1693  Try( PrimitiveACQ_POS_J_Viper850(q_cur.data, &timestamp) );
1694  time_cur = timestamp;
1695  q_cur.deg2rad();
1696 
1697  // Get the camera pose from the direct kinematics
1698  vpViper850::get_fMc(q_cur, fMc_cur);
1699 
1700  if ( ! first_time_getvel ) {
1701 
1702  switch (frame) {
1703  case vpRobot::CAMERA_FRAME: {
1704  // Compute the displacement of the camera since the previous call
1705  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1706 
1707  // Compute the velocity of the camera from this displacement
1708  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1709 
1710  break ;
1711  }
1712 
1713  case vpRobot::ARTICULAR_FRAME: {
1714  velocity = (q_cur - q_prev_getvel)
1715  / (time_cur - time_prev_getvel);
1716  break ;
1717  }
1718 
1719  case vpRobot::REFERENCE_FRAME: {
1720  // Compute the displacement of the camera since the previous call
1721  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1722 
1723  // Compute the velocity of the camera from this displacement
1724  vpColVector v;
1725  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1726 
1727  // Express this velocity in the reference frame
1728  vpVelocityTwistMatrix fVc(fMc_cur);
1729  velocity = fVc * v;
1730 
1731  break ;
1732  }
1733 
1734  case vpRobot::MIXT_FRAME: {
1735  // Compute the displacement of the camera since the previous call
1736  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1737 
1738  // Compute the ThetaU representation for the rotation
1739  vpRotationMatrix cRc;
1740  cMc.extract(cRc);
1741  vpThetaUVector thetaU;
1742  thetaU.buildFrom(cRc);
1743 
1744  for (unsigned int i=0; i < 3; i++) {
1745  // Compute the translation displacement in the reference frame
1746  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1747  // Update the rotation displacement in the camera frame
1748  velocity[i+3] = thetaU[i];
1749  }
1750 
1751  // Compute the velocity
1752  velocity /= (time_cur - time_prev_getvel);
1753  break ;
1754  }
1755  }
1756  }
1757  else {
1758  first_time_getvel = false;
1759  }
1760 
1761  // Memorize the camera pose for the next call
1762  fMc_prev_getvel = fMc_cur;
1763 
1764  // Memorize the joint position for the next call
1765  q_prev_getvel = q_cur;
1766 
1767  // Memorize the time associated to the joint position for the next call
1768  time_prev_getvel = time_cur;
1769 
1770 
1771  CatchPrint();
1772  if (TryStt < 0) {
1773  vpERROR_TRACE ("Cannot get velocity.");
1775  "Cannot get velocity.");
1776  }
1777 }
1778 
1788  vpColVector & velocity)
1789 {
1790  double timestamp;
1791  getVelocity(frame, velocity, timestamp);
1792 }
1793 
1845 {
1846  vpColVector velocity;
1847  getVelocity (frame, velocity, timestamp);
1848 
1849  return velocity;
1850 }
1851 
1861 {
1862  vpColVector velocity;
1863  double timestamp;
1864  getVelocity (frame, velocity, timestamp);
1865 
1866  return velocity;
1867 }
1868 
1934 bool
1935  vpRobotViper850::readPosFile(const char *filename, vpColVector &q)
1936 {
1937 
1938  FILE * fd ;
1939  fd = fopen(filename, "r") ;
1940  if (fd == NULL)
1941  return false;
1942 
1943  char line[FILENAME_MAX];
1944  char dummy[FILENAME_MAX];
1945  char head[] = "R:";
1946  bool sortie = false;
1947 
1948  do {
1949  // Saut des lignes commencant par #
1950  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1951  if ( strncmp (line, "#", 1) != 0) {
1952  // La ligne n'est pas un commentaire
1953  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1954  sortie = true; // Position robot trouvee.
1955  }
1956  // else
1957  // return (false); // fin fichier sans position robot.
1958  }
1959  }
1960  else {
1961  return (false); /* fin fichier */
1962  }
1963 
1964  }
1965  while ( sortie != true );
1966 
1967  // Lecture des positions
1968  q.resize(njoint);
1969  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1970  dummy,
1971  &q[0], &q[1], &q[2],
1972  &q[3], &q[4], &q[5]);
1973 
1974  // converts rotations from degrees into radians
1975  q.deg2rad();
1976 
1977  fclose(fd) ;
1978  return (true);
1979 }
1980 
2004 bool
2005  vpRobotViper850::savePosFile(const char *filename, const vpColVector &q)
2006 {
2007 
2008  FILE * fd ;
2009  fd = fopen(filename, "w") ;
2010  if (fd == NULL)
2011  return false;
2012 
2013  fprintf(fd, "\
2014 #Viper850 - Position - Version 1.00\n\
2015 #\n\
2016 # R: A B C D E F\n\
2017 # Joint position in degrees\n\
2018 #\n\
2019 #\n\n");
2020 
2021  // Save positions in mm and deg
2022  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2023  vpMath::deg(q[0]),
2024  vpMath::deg(q[1]),
2025  vpMath::deg(q[2]),
2026  vpMath::deg(q[3]),
2027  vpMath::deg(q[4]),
2028  vpMath::deg(q[5]));
2029 
2030  fclose(fd) ;
2031  return (true);
2032 }
2033 
2044 void
2045  vpRobotViper850::move(const char *filename)
2046 {
2047  vpColVector q;
2048 
2049  try {
2050  this->readPosFile(filename, q) ;
2052  this->setPositioningVelocity(10);
2054  }
2055  catch(...) {
2056  throw;
2057  }
2058 }
2059 
2073 void
2074  vpRobotViper850::getCameraDisplacement(vpColVector &displacement)
2075 {
2076  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2077 }
2089 void
2090  vpRobotViper850::getArticularDisplacement(vpColVector &displacement)
2091 {
2093 }
2094 
2115 void
2117  vpColVector &displacement)
2118 {
2119  displacement.resize (6);
2120  displacement = 0;
2121 
2122  double q[6];
2123  vpColVector q_cur(6);
2124  double timestamp;
2125 
2126  InitTry;
2127 
2128  // Get the current joint position
2129  Try( PrimitiveACQ_POS_Viper850(q, &timestamp) );
2130  for (unsigned int i=0; i < njoint; i ++) {
2131  q_cur[i] = q[i];
2132  }
2133 
2134  if ( ! first_time_getdis ) {
2135  switch (frame) {
2136  case vpRobot::CAMERA_FRAME: {
2137  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2138  return;
2139  break ;
2140  }
2141 
2142  case vpRobot::ARTICULAR_FRAME: {
2143  displacement = q_cur - q_prev_getdis;
2144  break ;
2145  }
2146 
2147  case vpRobot::REFERENCE_FRAME: {
2148  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2149  return;
2150  break ;
2151  }
2152 
2153  case vpRobot::MIXT_FRAME: {
2154  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2155  return;
2156  break ;
2157  }
2158  }
2159  }
2160  else {
2161  first_time_getdis = false;
2162  }
2163 
2164  // Memorize the joint position for the next call
2165  q_prev_getdis = q_cur;
2166 
2167  CatchPrint();
2168  if (TryStt < 0) {
2169  vpERROR_TRACE ("Cannot get velocity.");
2171  "Cannot get velocity.");
2172  }
2173 }
2174 
2188 void
2190 {
2191  InitTry;
2192 
2193  Try( PrimitiveTFS_BIAS_Viper850() );
2194 
2195  // Wait 500 ms to be sure the next measures take into account the bias
2196  vpTime::wait(500);
2197 
2198  CatchPrint();
2199  if (TryStt < 0) {
2200  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2202  "Cannot bias the force/torque sensor.");
2203  }
2204 }
2205 
2245 void
2247 {
2248  InitTry;
2249 
2250  H.resize (6);
2251 
2252  Try( PrimitiveTFS_ACQ_Viper850(H.data) );
2253 
2254  CatchPrint();
2255  if (TryStt < 0) {
2256  vpERROR_TRACE ("Cannot get the force/torque measures.");
2258  "Cannot get force/torque measures.");
2259  }
2260 }
2267 void
2269 {
2270  InitTry;
2271  Try( PrimitiveGripper_Viper850(1) );
2272  std::cout << "Open the gripper..." << std::endl;
2273  CatchPrint();
2274  if (TryStt < 0) {
2275  vpERROR_TRACE ("Cannot open the gripper");
2277  "Cannot open the gripper.");
2278  }
2279 }
2280 
2289 {
2290  InitTry;
2291  Try( PrimitiveGripper_Viper850(0) );
2292  std::cout << "Close the gripper..." << std::endl;
2293  CatchPrint();
2294  if (TryStt < 0) {
2295  vpERROR_TRACE ("Cannot close the gripper");
2297  "Cannot close the gripper.");
2298  }
2299 }
2300 
2307 {
2308  InitTry;
2309  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
2310  std::cout << "Enable joint limits on axis 6..." << std::endl;
2311  CatchPrint();
2312  if (TryStt < 0) {
2313  vpERROR_TRACE ("Cannot enable joint limits on axis 6");
2315  "Cannot enable joint limits on axis 6.");
2316  }
2317 }
2318 
2329 {
2330  InitTry;
2331  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1) );
2332  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2333  CatchPrint();
2334  if (TryStt < 0) {
2335  vpERROR_TRACE ("Cannot disable joint limits on axis 6");
2337  "Cannot disable joint limits on axis 6.");
2338  }
2339 }
2340 
2348 void
2350 {
2353 
2354  return;
2355 }
2356 
2376 void
2378 {
2379  maxRotationVelocity_joint6 = w6_max;
2380  return;
2381 }
2382 
2389 double
2391 {
2392  return maxRotationVelocity_joint6;
2393 }
2394 
2395 #elif !defined(VISP_BUILD_SHARED_LIBS)
2396 // Work arround to avoid warning: libvisp_robot.a(vpRobotViper850.cpp.o) has no symbols
2397 void dummy_vpRobotViper850() {};
2398 #endif
2399 
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocity(double w_max)
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:981
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:150
Error that can be emited by the vpRobot class and its derivates.
double getPositioningVelocity(void) const
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:95
void closeGripper() const
void getForceTorque(vpColVector &H) const
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
Definition: vpRobot.h:156
#define vpERROR_TRACE
Definition: vpDebug.h:391
void setPositioningVelocity(const double velocity)
double maxRotationVelocity
Definition: vpRobot.h:95
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
void enableJoint6Limits() const
void biasForceTorqueSensor() const
Initialize the position controller.
Definition: vpRobot.h:69
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
class that defines a generic virtual robot
Definition: vpRobot.h:58
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:84
vpControlFrameType
Definition: vpRobot.h:76
vpRxyzVector erc
Definition: vpViper.h:148
void get_eJe(vpMatrix &eJe)
static bool savePosFile(const char *filename, const vpColVector &q)
void disableJoint6Limits() const
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
void deg2rad()
Definition: vpColVector.h:124
Implementation of a rotation matrix and operations on such kind of matrices.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
static bool readPosFile(const char *filename, vpColVector &q)
Initialize the velocity controller.
Definition: vpRobot.h:68
vpRobotStateType
Definition: vpRobot.h:64
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
Definition: vpViper850.h:132
bool verbose_
Definition: vpRobot.h:113
vpTranslationVector etc
Definition: vpViper.h:147
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRowVector t() const
vpColVector joint_max
Definition: vpViper.h:159
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:87
Modelisation of the ADEPT Viper 850 robot.
Definition: vpViper850.h:62
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:611
bool getPowerState() const
Implementation of a velocity twist matrix and operations on such kind of matrices.
void get_fJe(vpMatrix &fJe)
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:573
static double rad(double deg)
Definition: vpMath.h:104
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1173
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:262
void get_cVe(vpVelocityTwistMatrix &cVe) const
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:927
void setMaxRotationVelocityJoint6(double w6_max)
static double deg(double rad)
Definition: vpMath.h:97
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Implementation of column vector and the associated operations.
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)
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:138
double getMaxRotationVelocityJoint6() const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
Emergency stop activated.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRzyzVector.h:151
virtual ~vpRobotViper850(void)
void init(void)
Definition: vpViper850.cpp:172
Automatic control mode (default).
double getTime() const
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void rad2deg()
Definition: vpColVector.h:202
void move(const char *filename)
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:142
void get_cMe(vpHomogeneousMatrix &cMe) const
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:217
vpColVector joint_min
Definition: vpViper.h:160