ViSP  2.10.0
vpRobotViper850.cpp
1 /****************************************************************************
2  *
3  * $Id: vpRobotViper850.cpp 4594 2014-01-20 15:08:07Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2014 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  maxRotationVelocity_joint6 = maxRotationVelocity;
222 
223  vpRobotViper850::robotAlreadyCreated = true;
224 
225  return ;
226 }
227 
228 
229 /* ------------------------------------------------------------------------ */
230 /* --- INITIALISATION ----------------------------------------------------- */
231 /* ------------------------------------------------------------------------ */
232 
252 void
254 {
255  InitTry;
256 
257  // Initialise private variables used to compute the measured velocities
258  q_prev_getvel.resize(6);
259  q_prev_getvel = 0;
260  time_prev_getvel = 0;
261  first_time_getvel = true;
262 
263  // Initialise private variables used to compute the measured displacement
264  q_prev_getdis.resize(6);
265  q_prev_getdis = 0;
266  first_time_getdis = true;
267 
268 
269  // Initialize the firewire connection
270  Try( InitializeConnection(verbose_) );
271 
272  // Connect to the servoboard using the servo board GUID
273  Try( InitializeNode_Viper850() );
274 
275  Try( PrimitiveRESET_Viper850() );
276 
277  // Enable the joint limits on axis 6
278  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
279 
280  // Update the eMc matrix in the low level controller
282 
283  // Look if the power is on or off
284  UInt32 HIPowerStatus;
285  UInt32 EStopStatus;
286  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
287  &HIPowerStatus));
288  CAL_Wait(0.1);
289 
290  // Print the robot status
291  if (verbose_) {
292  std::cout << "Robot status: ";
293  switch(EStopStatus) {
294  case ESTOP_AUTO:
295  controlMode = AUTO;
296  if (HIPowerStatus == 0)
297  std::cout << "Power is OFF" << std::endl;
298  else
299  std::cout << "Power is ON" << std::endl;
300  break;
301 
302  case ESTOP_MANUAL:
303  controlMode = MANUAL;
304  if (HIPowerStatus == 0)
305  std::cout << "Power is OFF" << std::endl;
306  else
307  std::cout << "Power is ON" << std::endl;
308  break;
309  case ESTOP_ACTIVATED:
310  controlMode = ESTOP;
311  std::cout << "Emergency stop is activated" << std::endl;
312  break;
313  default:
314  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
315  std::cout << "You have to call Adept for maintenance..." << std::endl;
316  // Free allocated resources
317  }
318  std::cout << std::endl;
319  }
320  // get real joint min/max from the MotionBlox
321  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
322  // Convert units from degrees to radians
323  joint_min.deg2rad();
324  joint_max.deg2rad();
325 
326  // for (unsigned int i=0; i < njoint; i++) {
327  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
328  // }
329 
330  // If an error occur in the low level controller, goto here
331  //CatchPrint();
332  Catch();
333 
334  // Test if an error occurs
335  if (TryStt == -20001)
336  printf("No connection detected. Check if the robot is powered on \n"
337  "and if the firewire link exist between the MotionBlox and this computer.\n");
338  else if (TryStt == -675)
339  printf(" Timeout enabling power...\n");
340 
341  if (TryStt < 0) {
342  // Power off the robot
343  PrimitivePOWEROFF_Viper850();
344  // Free allocated resources
345  ShutDownConnection();
346 
347  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
349  "Cannot open connexion with the motionblox");
350  }
351  return ;
352 }
353 
410 void
413 {
414 
415  InitTry;
416  // Read the robot constants from files
417  // - joint [min,max], coupl_56, long_56
418  // - camera extrinsic parameters relative to eMc
419  vpViper850::init(tool, projModel);
420 
421  // Set the camera constant (eMc pose) in the MotionBlox
422  double eMc_pose[6];
423  for (unsigned int i=0; i < 3; i ++) {
424  eMc_pose[i] = etc[i]; // translation in meters
425  eMc_pose[i+3] = erc[i]; // rotation in rad
426  }
427  // Update the eMc pose in the low level controller
428  Try( PrimitiveCONST_Viper850(eMc_pose) );
429 
430  // get real joint min/max from the MotionBlox
431  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
432  // Convert units from degrees to radians
433  joint_min.deg2rad();
434  joint_max.deg2rad();
435 
436  // for (unsigned int i=0; i < njoint; i++) {
437  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
438  // }
439 
440  setToolType(tool);
441 
442  CatchPrint();
443  return ;
444 }
445 
446 /* ------------------------------------------------------------------------ */
447 /* --- DESTRUCTOR --------------------------------------------------------- */
448 /* ------------------------------------------------------------------------ */
449 
457 {
458  InitTry;
459 
461 
462  // Look if the power is on or off
463  UInt32 HIPowerStatus;
464  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
465  &HIPowerStatus));
466  CAL_Wait(0.1);
467 
468  // if (HIPowerStatus == 1) {
469  // fprintf(stdout, "Power OFF the robot\n");
470  // fflush(stdout);
471 
472  // Try( PrimitivePOWEROFF_Viper850() );
473  // }
474 
475  // Free allocated resources
476  ShutDownConnection();
477 
478  vpRobotViper850::robotAlreadyCreated = false;
479 
480  CatchPrint();
481  return;
482 }
483 
484 
485 
486 
495 {
496  InitTry;
497 
498  switch (newState) {
499  case vpRobot::STATE_STOP: {
500  // Start primitive STOP only if the current state is Velocity
502  Try( PrimitiveSTOP_Viper850() );
503  }
504  break;
505  }
508  std::cout << "Change the control mode from velocity to position control.\n";
509  Try( PrimitiveSTOP_Viper850() );
510  }
511  else {
512  //std::cout << "Change the control mode from stop to position control.\n";
513  }
514  this->powerOn();
515  break;
516  }
519  std::cout << "Change the control mode from stop to velocity control.\n";
520  }
521  this->powerOn();
522  break;
523  }
524  default:
525  break ;
526  }
527 
528  CatchPrint();
529 
530  return vpRobot::setRobotState (newState);
531 }
532 
533 
534 /* ------------------------------------------------------------------------ */
535 /* --- STOP --------------------------------------------------------------- */
536 /* ------------------------------------------------------------------------ */
537 
545 void
547 {
549  return;
550 
551  InitTry;
552  Try( PrimitiveSTOP_Viper850() );
554 
555  CatchPrint();
556  if (TryStt < 0) {
557  vpERROR_TRACE ("Cannot stop robot motion");
559  "Cannot stop robot motion.");
560  }
561 }
562 
572 void
574 {
575  InitTry;
576 
577  // Look if the power is on or off
578  UInt32 HIPowerStatus;
579  UInt32 EStopStatus;
580  bool firsttime = true;
581  unsigned int nitermax = 10;
582 
583  for (unsigned int i=0; i<nitermax; i++) {
584  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
585  &HIPowerStatus));
586  if (EStopStatus == ESTOP_AUTO) {
587  controlMode = AUTO;
588  break; // exit for loop
589  }
590  else if (EStopStatus == ESTOP_MANUAL) {
591  controlMode = MANUAL;
592  break; // exit for loop
593  }
594  else if (EStopStatus == ESTOP_ACTIVATED) {
595  controlMode = ESTOP;
596  if (firsttime) {
597  std::cout << "Emergency stop is activated! \n"
598  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
599  firsttime = false;
600  }
601  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
602  fflush(stdout);
603  CAL_Wait(1);
604  }
605  else {
606  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
607  std::cout << "You have to call Adept for maintenance..." << std::endl;
608  // Free allocated resources
609  ShutDownConnection();
610  exit(0);
611  }
612  }
613 
614  if (EStopStatus == ESTOP_ACTIVATED)
615  std::cout << std::endl;
616 
617  if (EStopStatus == ESTOP_ACTIVATED) {
618  std::cout << "Sorry, cannot power on the robot." << std::endl;
620  "Cannot power on the robot.");
621  }
622 
623  if (HIPowerStatus == 0) {
624  fprintf(stdout, "Power ON the Viper850 robot\n");
625  fflush(stdout);
626 
627  Try( PrimitivePOWERON_Viper850() );
628  }
629 
630  CatchPrint();
631  if (TryStt < 0) {
632  vpERROR_TRACE ("Cannot power on the robot");
634  "Cannot power off the robot.");
635  }
636 }
637 
647 void
649 {
650  InitTry;
651 
652  // Look if the power is on or off
653  UInt32 HIPowerStatus;
654  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
655  &HIPowerStatus));
656  CAL_Wait(0.1);
657 
658  if (HIPowerStatus == 1) {
659  fprintf(stdout, "Power OFF the Viper850 robot\n");
660  fflush(stdout);
661 
662  Try( PrimitivePOWEROFF_Viper850() );
663  }
664 
665  CatchPrint();
666  if (TryStt < 0) {
667  vpERROR_TRACE ("Cannot power off the robot");
669  "Cannot power off the robot.");
670  }
671 }
672 
684 bool
686 {
687  InitTry;
688  bool status = false;
689  // Look if the power is on or off
690  UInt32 HIPowerStatus;
691  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
692  &HIPowerStatus));
693  CAL_Wait(0.1);
694 
695  if (HIPowerStatus == 1) {
696  status = true;
697  }
698 
699  CatchPrint();
700  if (TryStt < 0) {
701  vpERROR_TRACE ("Cannot get the power status");
703  "Cannot get the power status.");
704  }
705  return status;
706 }
707 
717 void
719 {
720  vpHomogeneousMatrix cMe ;
721  vpViper850::get_cMe(cMe) ;
722 
723  cVe.buildFrom(cMe) ;
724 }
725 
737 void
739 {
740  vpViper850::get_cMe(cMe) ;
741 }
742 
743 
755 void
757 {
758 
759  double position[6];
760  double timestamp;
761 
762  InitTry;
763  Try( PrimitiveACQ_POS_J_Viper850(position, &timestamp) );
764  CatchPrint();
765 
766  vpColVector q(6);
767  for (unsigned int i=0; i < njoint; i++)
768  q[i] = vpMath::rad(position[i]);
769 
770  try
771  {
772  vpViper850::get_eJe(q, eJe) ;
773  }
774  catch(...)
775  {
776  vpERROR_TRACE("catch exception ") ;
777  throw ;
778  }
779 }
792 void
794 {
795 
796  double position[6];
797  double timestamp;
798 
799  InitTry;
800  Try( PrimitiveACQ_POS_Viper850(position, &timestamp) );
801  CatchPrint();
802 
803  vpColVector q(6);
804  for (unsigned int i=0; i < njoint; i++)
805  q[i] = position[i];
806 
807  try
808  {
809  vpViper850::get_fJe(q, fJe) ;
810  }
811  catch(...)
812  {
813  vpERROR_TRACE("Error caught");
814  throw ;
815  }
816 }
817 
855 void
857 {
858  positioningVelocity = velocity;
859 }
860 
866 double
868 {
869  return positioningVelocity;
870 }
871 
872 
950 void
952  const vpColVector & position )
953 {
954 
956  {
957  vpERROR_TRACE ("Robot was not in position-based control\n"
958  "Modification of the robot state");
960  }
961 
962  vpColVector destination(njoint);
963  int error = 0;
964  double timestamp;
965 
966  InitTry;
967  switch(frame) {
968  case vpRobot::CAMERA_FRAME : {
969  vpColVector q(njoint);
970  Try( PrimitiveACQ_POS_Viper850(q.data, &timestamp) );
971 
972  // Convert degrees into rad
973  q.deg2rad();
974 
975  // Get fMc from the inverse kinematics
977  vpViper850::get_fMc(q, fMc);
978 
979  // Set cMc from the input position
980  vpTranslationVector txyz;
981  vpRxyzVector rxyz;
982  for (unsigned int i=0; i < 3; i++) {
983  txyz[i] = position[i];
984  rxyz[i] = position[i+3];
985  }
986 
987  // Compute cMc2
988  vpRotationMatrix cRc2(rxyz);
989  vpHomogeneousMatrix cMc2(txyz, cRc2);
990 
991  // Compute the new position to reach: fMc*cMc2
992  vpHomogeneousMatrix fMc2 = fMc * cMc2;
993 
994  // Compute the corresponding joint position from the inverse kinematics
995  unsigned int solution = this->getInverseKinematics(fMc2, q);
996  if (solution) { // Position is reachable
997  destination = q;
998  // convert rad to deg requested for the low level controller
999  destination.rad2deg();
1000  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
1001  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1002  }
1003  else {
1004  // Cartesian position is out of range
1005  error = -1;
1006  }
1007 
1008  break ;
1009  }
1010  case vpRobot::ARTICULAR_FRAME: {
1011  destination = position;
1012  // convert rad to deg requested for the low level controller
1013  destination.rad2deg();
1014 
1015  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1016  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
1017  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1018  break ;
1019 
1020  }
1021  case vpRobot::REFERENCE_FRAME: {
1022  // Convert angles from Rxyz representation to Rzyz representation
1023  vpRxyzVector rxyz(position[3],position[4],position[5]);
1024  vpRotationMatrix R(rxyz);
1025  vpRzyzVector rzyz(R);
1026 
1027  for (unsigned int i=0; i <3; i++) {
1028  destination[i] = position[i];
1029  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1030  }
1031  int configuration = 0; // keep the actual configuration
1032 
1033  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1034  Try( PrimitiveMOVE_C_Viper850(destination.data, configuration,
1035  positioningVelocity) );
1036  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1037 
1038  break ;
1039  }
1040  case vpRobot::MIXT_FRAME:
1041  {
1042  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1044  "Positionning error: "
1045  "Mixt frame not implemented.");
1046  break ;
1047  }
1048  }
1049 
1050  CatchPrint();
1051  if (TryStt == InvalidPosition || TryStt == -1023)
1052  std::cout << " : Position out of range.\n";
1053  else if (TryStt == -3019) {
1054  if (frame == vpRobot::ARTICULAR_FRAME)
1055  std::cout << " : Joint position out of range.\n";
1056  else
1057  std::cout << " : Cartesian position leads to a joint position out of range.\n";
1058  }
1059  else if (TryStt < 0)
1060  std::cout << " : Unknown error (see Fabien).\n";
1061  else if (error == -1)
1062  std::cout << "Position out of range.\n";
1063 
1064  if (TryStt < 0 || error < 0) {
1065  vpERROR_TRACE ("Positionning error.");
1067  "Position out of range.");
1068  }
1069 
1070  return ;
1071 }
1072 
1139  const double pos1,
1140  const double pos2,
1141  const double pos3,
1142  const double pos4,
1143  const double pos5,
1144  const double pos6)
1145 {
1146  try{
1147  vpColVector position(6) ;
1148  position[0] = pos1 ;
1149  position[1] = pos2 ;
1150  position[2] = pos3 ;
1151  position[3] = pos4 ;
1152  position[4] = pos5 ;
1153  position[5] = pos6 ;
1154 
1155  setPosition(frame, position) ;
1156  }
1157  catch(...)
1158  {
1159  vpERROR_TRACE("Error caught");
1160  throw ;
1161  }
1162 }
1163 
1203 void vpRobotViper850::setPosition(const char *filename)
1204 {
1205  vpColVector q;
1206  bool ret;
1207 
1208  ret = this->readPosFile(filename, q);
1209 
1210  if (ret == false) {
1211  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1213  "Bad position in filename.");
1214  }
1217 }
1218 
1288  vpColVector & position, double &timestamp)
1289 {
1290 
1291  InitTry;
1292 
1293  position.resize (6);
1294 
1295  switch (frame) {
1296  case vpRobot::CAMERA_FRAME : {
1297  position = 0;
1298  return;
1299  }
1300  case vpRobot::ARTICULAR_FRAME : {
1301  Try( PrimitiveACQ_POS_J_Viper850(position.data, &timestamp) );
1302  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1303  position.deg2rad();
1304 
1305  return;
1306  }
1307  case vpRobot::REFERENCE_FRAME : {
1308  Try( PrimitiveACQ_POS_C_Viper850(position.data, &timestamp) );
1309  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1310  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1311  // Convert Euler Rzyz angles from deg to rad
1312  for (unsigned int i=3; i <6; i++)
1313  position[i] = vpMath::rad(position[i]);
1314  // Convert Rzyz angles into Rxyz representation
1315  vpRzyzVector rzyz(position[3], position[4], position[5]);
1316  vpRotationMatrix R(rzyz);
1317  vpRxyzVector rxyz(R);
1318 
1319  // Update the position using Rxyz representation
1320  for (unsigned int i=0; i <3; i++)
1321  position[i+3] = rxyz[i];
1322  // vpCTRACE << "Cartesian position Rxyz (deg)"
1323  // << position[0] << " " << position[1] << " " << position[2] << " "
1324  // << vpMath::deg(position[3]) << " "
1325  // << vpMath::deg(position[4]) << " "
1326  // << vpMath::deg(position[5]) << std::endl;
1327 
1328  break ;
1329  }
1330  case vpRobot::MIXT_FRAME: {
1331  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1333  "Cannot get position in mixt frame: "
1334  "not implemented");
1335  break ;
1336  }
1337  }
1338 
1339  CatchPrint();
1340  if (TryStt < 0) {
1341  vpERROR_TRACE ("Cannot get position.");
1343  "Cannot get position.");
1344  }
1345 
1346  return;
1347 }
1348 
1353 {
1354  double timestamp;
1355  PrimitiveACQ_TIME_Viper850(&timestamp);
1356  return timestamp;
1357 }
1358 
1369  vpColVector & position)
1370 {
1371  double timestamp;
1372  getPosition(frame, position, timestamp);
1373 }
1374 
1386  vpPoseVector &position,
1387  double &timestamp)
1388 {
1389  vpColVector posRxyz;
1390  //recupere position en Rxyz
1391  this->getPosition(frame, posRxyz, timestamp);
1392  vpRxyzVector RxyzVect;
1393  for (unsigned int j=0;j<3;j++)
1394  RxyzVect[j]=posRxyz[j+3];
1395  //recupere le vecteur thetaU correspondant
1396  vpThetaUVector RtuVect(RxyzVect);
1397 
1398  //remplit le vpPoseVector avec translation et rotation ThetaU
1399  for (unsigned int j=0;j<3;j++)
1400  {
1401  position[j]=posRxyz[j];
1402  position[j+3]=RtuVect[j];
1403  }
1404 }
1405 
1416  vpPoseVector &position)
1417 {
1418  vpColVector posRxyz;
1419  double timestamp;
1420  //recupere position en Rxyz
1421  this->getPosition(frame, posRxyz, timestamp);
1422  vpRxyzVector RxyzVect;
1423  for (unsigned int j=0;j<3;j++)
1424  RxyzVect[j]=posRxyz[j+3];
1425  //recupere le vecteur thetaU correspondant
1426  vpThetaUVector RtuVect(RxyzVect);
1427 
1428  //remplit le vpPoseVector avec translation et rotation ThetaU
1429  for (unsigned int j=0;j<3;j++)
1430  {
1431  position[j]=posRxyz[j];
1432  position[j+3]=RtuVect[j];
1433  }
1434 }
1435 
1509  const vpColVector & vel)
1510 {
1512  vpERROR_TRACE ("Cannot send a velocity to the robot "
1513  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1515  "Cannot send a velocity to the robot "
1516  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1517  }
1518 
1519  vpColVector vel_sat(6);
1520 
1521  // Velocity saturation
1522  switch(frame) {
1523  // saturation in cartesian space
1524  case vpRobot::CAMERA_FRAME :
1526  case vpRobot::MIXT_FRAME : {
1527  vpColVector vel_max(6);
1528 
1529  for (unsigned int i=0; i<3; i++)
1530  vel_max[i] = getMaxTranslationVelocity();
1531  for (unsigned int i=3; i<6; i++)
1532  vel_max[i] = getMaxRotationVelocity();
1533 
1534  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1535 
1536  break;
1537  }
1538  // saturation in joint space
1539  case vpRobot::ARTICULAR_FRAME : {
1540  vpColVector vel_max(6);
1541 
1543  for (unsigned int i=0; i<6; i++)
1544  vel_max[i] = getMaxRotationVelocity();
1545  }
1546  else {
1547  for (unsigned int i=0; i<5; i++)
1548  vel_max[i] = getMaxRotationVelocity();
1549  vel_max[5] = getMaxRotationVelocityJoint6();
1550  }
1551 
1552  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1553  }
1554  }
1555 
1556  InitTry;
1557 
1558  switch(frame) {
1559  case vpRobot::CAMERA_FRAME : {
1560  // Send velocities in m/s and rad/s
1561  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1562  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPCAM_VIPER850) );
1563  break ;
1564  }
1565  case vpRobot::ARTICULAR_FRAME : {
1566  // Convert all the velocities from rad/s into deg/s
1567  vel_sat.rad2deg();
1568  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1569  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER850) );
1570  Try( PrimitiveMOVESPEED_Viper850(vel_sat.data) );
1571  break ;
1572  }
1573  case vpRobot::REFERENCE_FRAME : {
1574  // Send velocities in m/s and rad/s
1575  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1576  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPFIX_VIPER850) );
1577  break ;
1578  }
1579  case vpRobot::MIXT_FRAME : {
1580  //Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPMIX_VIPER850) );
1581  break ;
1582  }
1583  default: {
1584  vpERROR_TRACE ("Error in spec of vpRobot. "
1585  "Case not taken in account.");
1586  return;
1587  }
1588  }
1589 
1590  Catch();
1591  if (TryStt < 0) {
1592  if (TryStt == VelStopOnJoint) {
1593  UInt32 axisInJoint[njoint];
1594  PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1595  for (unsigned int i=0; i < njoint; i ++) {
1596  if (axisInJoint[i])
1597  std::cout << "\nWarning: Velocity control stopped: axis "
1598  << i+1 << " on joint limit!" <<std::endl;
1599  }
1600  }
1601  else {
1602  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1603  if (TryString != NULL) {
1604  // The statement is in TryString, but we need to check the validity
1605  printf(" Error sentence %s\n", TryString); // Print the TryString
1606  }
1607  else {
1608  printf("\n");
1609  }
1610  }
1611  }
1612 
1613  return;
1614 }
1615 
1616 
1617 
1618 
1619 
1620 
1621 /* ------------------------------------------------------------------------ */
1622 /* --- GET ---------------------------------------------------------------- */
1623 /* ------------------------------------------------------------------------ */
1624 
1625 
1683  vpColVector & velocity, double &timestamp)
1684 {
1685 
1686  velocity.resize (6);
1687  velocity = 0;
1688 
1689  vpColVector q_cur(6);
1690  vpHomogeneousMatrix fMc_cur;
1691  vpHomogeneousMatrix cMc; // camera displacement
1692  double time_cur;
1693 
1694  InitTry;
1695 
1696  // Get the current joint position
1697  Try( PrimitiveACQ_POS_J_Viper850(q_cur.data, &timestamp) );
1698  time_cur = timestamp;
1699  q_cur.deg2rad();
1700 
1701  // Get the camera pose from the direct kinematics
1702  vpViper850::get_fMc(q_cur, fMc_cur);
1703 
1704  if ( ! first_time_getvel ) {
1705 
1706  switch (frame) {
1707  case vpRobot::CAMERA_FRAME: {
1708  // Compute the displacement of the camera since the previous call
1709  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1710 
1711  // Compute the velocity of the camera from this displacement
1712  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1713 
1714  break ;
1715  }
1716 
1717  case vpRobot::ARTICULAR_FRAME: {
1718  velocity = (q_cur - q_prev_getvel)
1719  / (time_cur - time_prev_getvel);
1720  break ;
1721  }
1722 
1723  case vpRobot::REFERENCE_FRAME: {
1724  // Compute the displacement of the camera since the previous call
1725  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1726 
1727  // Compute the velocity of the camera from this displacement
1728  vpColVector v;
1729  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1730 
1731  // Express this velocity in the reference frame
1732  vpVelocityTwistMatrix fVc(fMc_cur);
1733  velocity = fVc * v;
1734 
1735  break ;
1736  }
1737 
1738  case vpRobot::MIXT_FRAME: {
1739  // Compute the displacement of the camera since the previous call
1740  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1741 
1742  // Compute the ThetaU representation for the rotation
1743  vpRotationMatrix cRc;
1744  cMc.extract(cRc);
1745  vpThetaUVector thetaU;
1746  thetaU.buildFrom(cRc);
1747 
1748  for (unsigned int i=0; i < 3; i++) {
1749  // Compute the translation displacement in the reference frame
1750  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1751  // Update the rotation displacement in the camera frame
1752  velocity[i+3] = thetaU[i];
1753  }
1754 
1755  // Compute the velocity
1756  velocity /= (time_cur - time_prev_getvel);
1757  break ;
1758  }
1759  }
1760  }
1761  else {
1762  first_time_getvel = false;
1763  }
1764 
1765  // Memorize the camera pose for the next call
1766  fMc_prev_getvel = fMc_cur;
1767 
1768  // Memorize the joint position for the next call
1769  q_prev_getvel = q_cur;
1770 
1771  // Memorize the time associated to the joint position for the next call
1772  time_prev_getvel = time_cur;
1773 
1774 
1775  CatchPrint();
1776  if (TryStt < 0) {
1777  vpERROR_TRACE ("Cannot get velocity.");
1779  "Cannot get velocity.");
1780  }
1781 }
1782 
1792  vpColVector & velocity)
1793 {
1794  double timestamp;
1795  getVelocity(frame, velocity, timestamp);
1796 }
1797 
1849 {
1850  vpColVector velocity;
1851  getVelocity (frame, velocity, timestamp);
1852 
1853  return velocity;
1854 }
1855 
1865 {
1866  vpColVector velocity;
1867  double timestamp;
1868  getVelocity (frame, velocity, timestamp);
1869 
1870  return velocity;
1871 }
1872 
1938 bool
1939  vpRobotViper850::readPosFile(const char *filename, vpColVector &q)
1940 {
1941 
1942  FILE * fd ;
1943  fd = fopen(filename, "r") ;
1944  if (fd == NULL)
1945  return false;
1946 
1947  char line[FILENAME_MAX];
1948  char dummy[FILENAME_MAX];
1949  char head[] = "R:";
1950  bool sortie = false;
1951 
1952  do {
1953  // Saut des lignes commencant par #
1954  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1955  if ( strncmp (line, "#", 1) != 0) {
1956  // La ligne n'est pas un commentaire
1957  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1958  sortie = true; // Position robot trouvee.
1959  }
1960  // else
1961  // return (false); // fin fichier sans position robot.
1962  }
1963  }
1964  else {
1965  return (false); /* fin fichier */
1966  }
1967 
1968  }
1969  while ( sortie != true );
1970 
1971  // Lecture des positions
1972  q.resize(njoint);
1973  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1974  dummy,
1975  &q[0], &q[1], &q[2],
1976  &q[3], &q[4], &q[5]);
1977 
1978  // converts rotations from degrees into radians
1979  q.deg2rad();
1980 
1981  fclose(fd) ;
1982  return (true);
1983 }
1984 
2008 bool
2009  vpRobotViper850::savePosFile(const char *filename, const vpColVector &q)
2010 {
2011 
2012  FILE * fd ;
2013  fd = fopen(filename, "w") ;
2014  if (fd == NULL)
2015  return false;
2016 
2017  fprintf(fd, "\
2018 #Viper850 - Position - Version 1.00\n\
2019 #\n\
2020 # R: A B C D E F\n\
2021 # Joint position in degrees\n\
2022 #\n\
2023 #\n\n");
2024 
2025  // Save positions in mm and deg
2026  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2027  vpMath::deg(q[0]),
2028  vpMath::deg(q[1]),
2029  vpMath::deg(q[2]),
2030  vpMath::deg(q[3]),
2031  vpMath::deg(q[4]),
2032  vpMath::deg(q[5]));
2033 
2034  fclose(fd) ;
2035  return (true);
2036 }
2037 
2048 void
2049  vpRobotViper850::move(const char *filename)
2050 {
2051  vpColVector q;
2052 
2053  try {
2054  this->readPosFile(filename, q) ;
2056  this->setPositioningVelocity(10);
2058  }
2059  catch(...) {
2060  throw;
2061  }
2062 }
2063 
2077 void
2078  vpRobotViper850::getCameraDisplacement(vpColVector &displacement)
2079 {
2080  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2081 }
2093 void
2094  vpRobotViper850::getArticularDisplacement(vpColVector &displacement)
2095 {
2097 }
2098 
2119 void
2121  vpColVector &displacement)
2122 {
2123  displacement.resize (6);
2124  displacement = 0;
2125 
2126  double q[6];
2127  vpColVector q_cur(6);
2128  double timestamp;
2129 
2130  InitTry;
2131 
2132  // Get the current joint position
2133  Try( PrimitiveACQ_POS_Viper850(q, &timestamp) );
2134  for (unsigned int i=0; i < njoint; i ++) {
2135  q_cur[i] = q[i];
2136  }
2137 
2138  if ( ! first_time_getdis ) {
2139  switch (frame) {
2140  case vpRobot::CAMERA_FRAME: {
2141  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2142  return;
2143  break ;
2144  }
2145 
2146  case vpRobot::ARTICULAR_FRAME: {
2147  displacement = q_cur - q_prev_getdis;
2148  break ;
2149  }
2150 
2151  case vpRobot::REFERENCE_FRAME: {
2152  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2153  return;
2154  break ;
2155  }
2156 
2157  case vpRobot::MIXT_FRAME: {
2158  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2159  return;
2160  break ;
2161  }
2162  }
2163  }
2164  else {
2165  first_time_getdis = false;
2166  }
2167 
2168  // Memorize the joint position for the next call
2169  q_prev_getdis = q_cur;
2170 
2171  CatchPrint();
2172  if (TryStt < 0) {
2173  vpERROR_TRACE ("Cannot get velocity.");
2175  "Cannot get velocity.");
2176  }
2177 }
2178 
2192 void
2194 {
2195  InitTry;
2196 
2197  Try( PrimitiveTFS_BIAS_Viper850() );
2198 
2199  // Wait 500 ms to be sure the next measures take into account the bias
2200  vpTime::wait(500);
2201 
2202  CatchPrint();
2203  if (TryStt < 0) {
2204  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2206  "Cannot bias the force/torque sensor.");
2207  }
2208 }
2209 
2249 void
2251 {
2252  InitTry;
2253 
2254  H.resize (6);
2255 
2256  Try( PrimitiveTFS_ACQ_Viper850(H.data) );
2257 
2258  CatchPrint();
2259  if (TryStt < 0) {
2260  vpERROR_TRACE ("Cannot get the force/torque measures.");
2262  "Cannot get force/torque measures.");
2263  }
2264 }
2271 void
2273 {
2274  InitTry;
2275  Try( PrimitiveGripper_Viper850(1) );
2276  std::cout << "Open the gripper..." << std::endl;
2277  CatchPrint();
2278  if (TryStt < 0) {
2279  vpERROR_TRACE ("Cannot open the gripper");
2281  "Cannot open the gripper.");
2282  }
2283 }
2284 
2293 {
2294  InitTry;
2295  Try( PrimitiveGripper_Viper850(0) );
2296  std::cout << "Close the gripper..." << std::endl;
2297  CatchPrint();
2298  if (TryStt < 0) {
2299  vpERROR_TRACE ("Cannot close the gripper");
2301  "Cannot close the gripper.");
2302  }
2303 }
2304 
2311 {
2312  InitTry;
2313  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
2314  std::cout << "Enable joint limits on axis 6..." << std::endl;
2315  CatchPrint();
2316  if (TryStt < 0) {
2317  vpERROR_TRACE ("Cannot enable joint limits on axis 6");
2319  "Cannot enable joint limits on axis 6.");
2320  }
2321 }
2322 
2333 {
2334  InitTry;
2335  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1) );
2336  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2337  CatchPrint();
2338  if (TryStt < 0) {
2339  vpERROR_TRACE ("Cannot disable joint limits on axis 6");
2341  "Cannot disable joint limits on axis 6.");
2342  }
2343 }
2344 
2352 void
2354 {
2357 
2358  return;
2359 }
2360 
2380 void
2382 {
2383  maxRotationVelocity_joint6 = w6_max;
2384  return;
2385 }
2386 
2393 double
2395 {
2396  return maxRotationVelocity_joint6;
2397 }
2398 
2399 #endif
2400 
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocity(double w_max)
static vpColVector inverse(const vpHomogeneousMatrix &M)
Definition of the vpMatrix class.
Definition: vpMatrix.h:98
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:985
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:99
void closeGripper() const
void getForceTorque(vpColVector &H) const
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:395
void setVerbose(bool verbose)
Definition: vpRobot.h:158
void setPositioningVelocity(const double velocity)
double maxRotationVelocity
Definition: vpRobot.h:97
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:254
void enableJoint6Limits() const
void biasForceTorqueSensor() const
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:167
vpControlFrameType
Definition: vpRobot.h:78
vpRxyzVector erc
Definition: vpViper.h:149
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)
void disableJoint6Limits() const
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:279
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:205
void deg2rad()
Definition: vpColVector.h:192
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:118
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:148
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRowVector t() const
Transpose of a vector.
vpColVector joint_max
Definition: vpViper.h:160
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
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:615
bool getPowerState() const
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
void get_fJe(vpMatrix &fJe)
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:577
static double rad(double deg)
Definition: vpMath.h:100
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1177
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:266
void get_cVe(vpVelocityTwistMatrix &cVe) const
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:931
void setMaxRotationVelocityJoint6(double w6_max)
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)
The pose is a complete representation of every rigid motion in the euclidian space.
Definition: vpPoseVector.h:92
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:140
double getMaxRotationVelocityJoint6() const
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:176
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:182
void move(const char *filename)
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:143
void get_cMe(vpHomogeneousMatrix &cMe) const
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:98
vpColVector joint_min
Definition: vpViper.h:161