ViSP  2.10.0
vpRobotViper650.cpp
1 /****************************************************************************
2  *
3  * $Id: vpRobotViper650.cpp 4793 2014-07-21 15:10:52Z 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 S650 robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
42 #include <visp/vpConfig.h>
43 
44 #ifdef VISP_HAVE_VIPER650
45 
46 #include <signal.h>
47 #include <stdlib.h>
48 #include <sys/types.h>
49 #include <unistd.h>
50 
51 #include <visp/vpRobotException.h>
52 #include <visp/vpExponentialMap.h>
53 #include <visp/vpDebug.h>
54 #include <visp/vpVelocityTwistMatrix.h>
55 #include <visp/vpThetaUVector.h>
56 #include <visp/vpRobot.h>
57 #include <visp/vpRobotViper650.h>
58 
59 /* ---------------------------------------------------------------------- */
60 /* --- STATIC ----------------------------------------------------------- */
61 /* ---------------------------------------------------------------------- */
62 
63 bool vpRobotViper650::robotAlreadyCreated = false;
64 
73 
74 /* ---------------------------------------------------------------------- */
75 /* --- EMERGENCY STOP --------------------------------------------------- */
76 /* ---------------------------------------------------------------------- */
77 
85 void emergencyStopViper650(int signo)
86 {
87  std::cout << "Stop the Viper650 application by signal ("
88  << signo << "): " << (char)7 ;
89  switch(signo)
90  {
91  case SIGINT:
92  std::cout << "SIGINT (stop by ^C) " << std::endl ; break ;
93  case SIGBUS:
94  std::cout <<"SIGBUS (stop due to a bus error) " << std::endl ; break ;
95  case SIGSEGV:
96  std::cout <<"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
97  case SIGKILL:
98  std::cout <<"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
99  case SIGQUIT:
100  std::cout <<"SIGQUIT " << std::endl ; break ;
101  default :
102  std::cout << signo << std::endl ;
103 }
104  //std::cout << "Emergency stop called\n";
105  // PrimitiveESTOP_Viper650();
106  PrimitiveSTOP_Viper650();
107  std::cout << "Robot was stopped\n";
108 
109  // Free allocated resources
110  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
111 
112  fprintf(stdout, "Application ");
113  fflush(stdout);
114  kill(getpid(), SIGKILL);
115  exit(1) ;
116 }
117 
118 /* ---------------------------------------------------------------------- */
119 /* --- CONSTRUCTOR ------------------------------------------------------ */
120 /* ---------------------------------------------------------------------- */
121 
177 vpRobotViper650::vpRobotViper650 (bool verbose)
178  :
179  vpViper650 (),
180  vpRobot ()
181 {
182 
183  /*
184  #define SIGHUP 1 // hangup
185  #define SIGINT 2 // interrupt (rubout)
186  #define SIGQUIT 3 // quit (ASCII FS)
187  #define SIGILL 4 // illegal instruction (not reset when caught)
188  #define SIGTRAP 5 // trace trap (not reset when caught)
189  #define SIGIOT 6 // IOT instruction
190  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
191  #define SIGEMT 7 // EMT instruction
192  #define SIGFPE 8 // floating point exception
193  #define SIGKILL 9 // kill (cannot be caught or ignored)
194  #define SIGBUS 10 // bus error
195  #define SIGSEGV 11 // segmentation violation
196  #define SIGSYS 12 // bad argument to system call
197  #define SIGPIPE 13 // write on a pipe with no one to read it
198  #define SIGALRM 14 // alarm clock
199  #define SIGTERM 15 // software termination signal from kill
200  */
201 
202  signal(SIGINT, emergencyStopViper650);
203  signal(SIGBUS, emergencyStopViper650) ;
204  signal(SIGSEGV, emergencyStopViper650) ;
205  signal(SIGKILL, emergencyStopViper650);
206  signal(SIGQUIT, emergencyStopViper650);
207 
208  setVerbose(verbose);
209  if (verbose_)
210  std::cout << "Open communication with MotionBlox.\n";
211  try {
212  this->init();
214  }
215  catch(...) {
216  // vpERROR_TRACE("Error caught") ;
217  throw ;
218  }
219  positioningVelocity = defaultPositioningVelocity ;
220 
221  maxRotationVelocity_joint6 = maxRotationVelocity;
222 
223  vpRobotViper650::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  // Initialize the firewire connection
269  Try( InitializeConnection(verbose_) );
270 
271  // Connect to the servoboard using the servo board GUID
272  Try( InitializeNode_Viper650() );
273 
274  Try( PrimitiveRESET_Viper650() );
275 
276  // Enable the joint limits on axis 6
277  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
278 
279  // Update the eMc matrix in the low level controller
281 
282  // Look if the power is on or off
283  UInt32 HIPowerStatus;
284  UInt32 EStopStatus;
285  Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
286  &HIPowerStatus));
287  CAL_Wait(0.1);
288 
289  // Print the robot status
290  if (verbose_) {
291  std::cout << "Robot status: ";
292  switch(EStopStatus) {
293  case ESTOP_AUTO:
294  controlMode = AUTO;
295  if (HIPowerStatus == 0)
296  std::cout << "Power is OFF" << std::endl;
297  else
298  std::cout << "Power is ON" << std::endl;
299  break;
300 
301  case ESTOP_MANUAL:
302  controlMode = MANUAL;
303  if (HIPowerStatus == 0)
304  std::cout << "Power is OFF" << std::endl;
305  else
306  std::cout << "Power is ON" << std::endl;
307  break;
308  case ESTOP_ACTIVATED:
309  controlMode = ESTOP;
310  std::cout << "Emergency stop is activated" << std::endl;
311  break;
312  default:
313  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
314  std::cout << "You have to call Adept for maintenance..." << std::endl;
315  // Free allocated resources
316  }
317  std::cout << std::endl;
318  }
319  // get real joint min/max from the MotionBlox
320  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
321  // Convert units from degrees to radians
322  joint_min.deg2rad();
323  joint_max.deg2rad();
324 
325  // for (unsigned int i=0; i < njoint; i++) {
326  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
327  // }
328 
329  // If an error occur in the low level controller, goto here
330  //CatchPrint();
331  Catch();
332 
333  // Test if an error occurs
334  if (TryStt == -20001)
335  printf("No connection detected. Check if the robot is powered on \n"
336  "and if the firewire link exist between the MotionBlox and this computer.\n");
337  else if (TryStt == -675)
338  printf(" Timeout enabling power...\n");
339 
340  if (TryStt < 0) {
341  // Power off the robot
342  PrimitivePOWEROFF_Viper650();
343  // Free allocated resources
344  ShutDownConnection();
345 
346  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
348  "Cannot open connexion with the motionblox");
349  }
350  return ;
351 }
352 
409 void
412 {
413 
414  InitTry;
415  // Read the robot constants from files
416  // - joint [min,max], coupl_56, long_56
417  // - camera extrinsic parameters relative to eMc
418  vpViper650::init(tool, projModel);
419 
420  // Set the camera constant (eMc pose) in the MotionBlox
421  double eMc_pose[6];
422  for (unsigned int i=0; i < 3; i ++) {
423  eMc_pose[i] = etc[i]; // translation in meters
424  eMc_pose[i+3] = erc[i]; // rotation in rad
425  }
426  // Update the eMc pose in the low level controller
427  Try( PrimitiveCONST_Viper650(eMc_pose) );
428 
429  // get real joint min/max from the MotionBlox
430  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
431  // Convert units from degrees to radians
432  joint_min.deg2rad();
433  joint_max.deg2rad();
434 
435  // for (unsigned int i=0; i < njoint; i++) {
436  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
437  // }
438 
439  setToolType(tool);
440 
441  CatchPrint();
442  return ;
443 }
444 
445 /* ------------------------------------------------------------------------ */
446 /* --- DESTRUCTOR --------------------------------------------------------- */
447 /* ------------------------------------------------------------------------ */
448 
456 {
457  InitTry;
458 
460 
461  // Look if the power is on or off
462  UInt32 HIPowerStatus;
463  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
464  &HIPowerStatus));
465  CAL_Wait(0.1);
466 
467  // if (HIPowerStatus == 1) {
468  // fprintf(stdout, "Power OFF the robot\n");
469  // fflush(stdout);
470 
471  // Try( PrimitivePOWEROFF_Viper650() );
472  // }
473 
474  // Free allocated resources
475  ShutDownConnection();
476 
477  vpRobotViper650::robotAlreadyCreated = false;
478 
479  CatchPrint();
480  return;
481 }
482 
483 
484 
485 
494 {
495  InitTry;
496 
497  switch (newState) {
498  case vpRobot::STATE_STOP: {
499  // Start primitive STOP only if the current state is Velocity
501  Try( PrimitiveSTOP_Viper650() );
502  }
503  break;
504  }
507  std::cout << "Change the control mode from velocity to position control.\n";
508  Try( PrimitiveSTOP_Viper650() );
509  }
510  else {
511  //std::cout << "Change the control mode from stop to position control.\n";
512  }
513  this->powerOn();
514  break;
515  }
518  std::cout << "Change the control mode from stop to velocity control.\n";
519  }
520  this->powerOn();
521  break;
522  }
523  default:
524  break ;
525  }
526 
527  CatchPrint();
528 
529  return vpRobot::setRobotState (newState);
530 }
531 
532 
533 /* ------------------------------------------------------------------------ */
534 /* --- STOP --------------------------------------------------------------- */
535 /* ------------------------------------------------------------------------ */
536 
544 void
546 {
548  return;
549 
550  InitTry;
551  Try( PrimitiveSTOP_Viper650() );
553 
554  CatchPrint();
555  if (TryStt < 0) {
556  vpERROR_TRACE ("Cannot stop robot motion");
558  "Cannot stop robot motion.");
559  }
560 }
561 
571 void
573 {
574  InitTry;
575 
576  // Look if the power is on or off
577  UInt32 HIPowerStatus;
578  UInt32 EStopStatus;
579  bool firsttime = true;
580  unsigned int nitermax = 10;
581 
582  for (unsigned int i=0; i<nitermax; i++) {
583  Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
584  &HIPowerStatus));
585  if (EStopStatus == ESTOP_AUTO) {
586  controlMode = AUTO;
587  break; // exit for loop
588  }
589  else if (EStopStatus == ESTOP_MANUAL) {
590  controlMode = MANUAL;
591  break; // exit for loop
592  }
593  else if (EStopStatus == ESTOP_ACTIVATED) {
594  controlMode = ESTOP;
595  if (firsttime) {
596  std::cout << "Emergency stop is activated! \n"
597  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
598  firsttime = false;
599  }
600  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
601  fflush(stdout);
602  CAL_Wait(1);
603  }
604  else {
605  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
606  std::cout << "You have to call Adept for maintenance..." << std::endl;
607  // Free allocated resources
608  ShutDownConnection();
609  exit(0);
610  }
611  }
612 
613  if (EStopStatus == ESTOP_ACTIVATED)
614  std::cout << std::endl;
615 
616  if (EStopStatus == ESTOP_ACTIVATED) {
617  std::cout << "Sorry, cannot power on the robot." << std::endl;
619  "Cannot power on the robot.");
620  }
621 
622  if (HIPowerStatus == 0) {
623  fprintf(stdout, "Power ON the Viper650 robot\n");
624  fflush(stdout);
625 
626  Try( PrimitivePOWERON_Viper650() );
627  }
628 
629  CatchPrint();
630  if (TryStt < 0) {
631  vpERROR_TRACE ("Cannot power on the robot");
633  "Cannot power off the robot.");
634  }
635 }
636 
646 void
648 {
649  InitTry;
650 
651  // Look if the power is on or off
652  UInt32 HIPowerStatus;
653  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
654  &HIPowerStatus));
655  CAL_Wait(0.1);
656 
657  if (HIPowerStatus == 1) {
658  fprintf(stdout, "Power OFF the Viper650 robot\n");
659  fflush(stdout);
660 
661  Try( PrimitivePOWEROFF_Viper650() );
662  }
663 
664  CatchPrint();
665  if (TryStt < 0) {
666  vpERROR_TRACE ("Cannot power off the robot");
668  "Cannot power off the robot.");
669  }
670 }
671 
683 bool
685 {
686  InitTry;
687  bool status = false;
688  // Look if the power is on or off
689  UInt32 HIPowerStatus;
690  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
691  &HIPowerStatus));
692  CAL_Wait(0.1);
693 
694  if (HIPowerStatus == 1) {
695  status = true;
696  }
697 
698  CatchPrint();
699  if (TryStt < 0) {
700  vpERROR_TRACE ("Cannot get the power status");
702  "Cannot get the power status.");
703  }
704  return status;
705 }
706 
716 void
718 {
719  vpHomogeneousMatrix cMe ;
720  vpViper650::get_cMe(cMe) ;
721 
722  cVe.buildFrom(cMe) ;
723 }
724 
736 void
738 {
739  vpViper650::get_cMe(cMe) ;
740 }
741 
742 
754 void
756 {
757 
758  double position[6];
759  double timestamp;
760 
761  InitTry;
762  Try( PrimitiveACQ_POS_J_Viper650(position, &timestamp) );
763  CatchPrint();
764 
765  vpColVector q(6);
766  for (unsigned int i=0; i < njoint; i++)
767  q[i] = vpMath::rad(position[i]);
768 
769  try
770  {
771  vpViper650::get_eJe(q, eJe) ;
772  }
773  catch(...)
774  {
775  vpERROR_TRACE("catch exception ") ;
776  throw ;
777  }
778 }
791 void
793 {
794 
795  double position[6];
796  double timestamp;
797 
798  InitTry;
799  Try( PrimitiveACQ_POS_Viper650(position, &timestamp) );
800  CatchPrint();
801 
802  vpColVector q(6);
803  for (unsigned int i=0; i < njoint; i++)
804  q[i] = position[i];
805 
806  try
807  {
808  vpViper650::get_fJe(q, fJe) ;
809  }
810  catch(...)
811  {
812  vpERROR_TRACE("Error caught");
813  throw ;
814  }
815 }
816 
854 void
856 {
857  positioningVelocity = velocity;
858 }
859 
865 double
867 {
868  return positioningVelocity;
869 }
870 
871 
949 void
951  const vpColVector & position )
952 {
953 
955  {
956  vpERROR_TRACE ("Robot was not in position-based control\n"
957  "Modification of the robot state");
959  }
960 
961  vpColVector destination(njoint);
962  int error = 0;
963  double timestamp;
964 
965  InitTry;
966  switch(frame) {
967  case vpRobot::CAMERA_FRAME : {
968  vpColVector q(njoint);
969  Try( PrimitiveACQ_POS_Viper650(q.data, &timestamp) );
970 
971  // Convert degrees into rad
972  q.deg2rad();
973 
974  // Get fMc from the inverse kinematics
976  vpViper650::get_fMc(q, fMc);
977 
978  // Set cMc from the input position
979  vpTranslationVector txyz;
980  vpRxyzVector rxyz;
981  for (unsigned int i=0; i < 3; i++) {
982  txyz[i] = position[i];
983  rxyz[i] = position[i+3];
984  }
985 
986  // Compute cMc2
987  vpRotationMatrix cRc2(rxyz);
988  vpHomogeneousMatrix cMc2(txyz, cRc2);
989 
990  // Compute the new position to reach: fMc*cMc2
991  vpHomogeneousMatrix fMc2 = fMc * cMc2;
992 
993  // Compute the corresponding joint position from the inverse kinematics
994  unsigned int solution = this->getInverseKinematics(fMc2, q);
995  if (solution) { // Position is reachable
996  destination = q;
997  // convert rad to deg requested for the low level controller
998  destination.rad2deg();
999  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
1000  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1001  }
1002  else {
1003  // Cartesian position is out of range
1004  error = -1;
1005  }
1006 
1007  break ;
1008  }
1009  case vpRobot::ARTICULAR_FRAME: {
1010  destination = position;
1011  // convert rad to deg requested for the low level controller
1012  destination.rad2deg();
1013 
1014  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1015  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
1016  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1017  break ;
1018 
1019  }
1020  case vpRobot::REFERENCE_FRAME: {
1021  // Convert angles from Rxyz representation to Rzyz representation
1022  vpRxyzVector rxyz(position[3],position[4],position[5]);
1023  vpRotationMatrix R(rxyz);
1024  vpRzyzVector rzyz(R);
1025 
1026  for (unsigned int i=0; i <3; i++) {
1027  destination[i] = position[i];
1028  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1029  }
1030  int configuration = 0; // keep the actual configuration
1031 
1032  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1033  Try( PrimitiveMOVE_C_Viper650(destination.data, configuration,
1034  positioningVelocity) );
1035  Try( WaitState_Viper650(ETAT_ATTENTE_AFMA6, 1000) );
1036 
1037  break ;
1038  }
1039  case vpRobot::MIXT_FRAME:
1040  {
1041  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1043  "Positionning error: "
1044  "Mixt frame not implemented.");
1045  break ;
1046  }
1047  }
1048 
1049  CatchPrint();
1050  if (TryStt == InvalidPosition || TryStt == -1023)
1051  std::cout << " : Position out of range.\n";
1052 
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 vpRobotViper650::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,
1289  double &timestamp)
1290 {
1291 
1292  InitTry;
1293 
1294  position.resize (6);
1295 
1296  switch (frame) {
1297  case vpRobot::CAMERA_FRAME : {
1298  position = 0;
1299  return;
1300  }
1301  case vpRobot::ARTICULAR_FRAME : {
1302  Try( PrimitiveACQ_POS_J_Viper650(position.data, &timestamp) );
1303  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1304  position.deg2rad();
1305 
1306  return;
1307  }
1308  case vpRobot::REFERENCE_FRAME : {
1309  Try( PrimitiveACQ_POS_C_Viper650(position.data, &timestamp) );
1310  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1311  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1312  // Convert Euler Rzyz angles from deg to rad
1313  for (unsigned int i=3; i <6; i++)
1314  position[i] = vpMath::rad(position[i]);
1315  // Convert Rzyz angles into Rxyz representation
1316  vpRzyzVector rzyz(position[3], position[4], position[5]);
1317  vpRotationMatrix R(rzyz);
1318  vpRxyzVector rxyz(R);
1319 
1320  // Update the position using Rxyz representation
1321  for (unsigned int i=0; i <3; i++)
1322  position[i+3] = rxyz[i];
1323  // vpCTRACE << "Cartesian position Rxyz (deg)"
1324  // << position[0] << " " << position[1] << " " << position[2] << " "
1325  // << vpMath::deg(position[3]) << " "
1326  // << vpMath::deg(position[4]) << " "
1327  // << vpMath::deg(position[5]) << std::endl;
1328 
1329  break ;
1330  }
1331  case vpRobot::MIXT_FRAME: {
1332  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1334  "Cannot get position in mixt frame: "
1335  "not implemented");
1336  break ;
1337  }
1338  }
1339 
1340  CatchPrint();
1341  if (TryStt < 0) {
1342  vpERROR_TRACE ("Cannot get position.");
1344  "Cannot get position.");
1345  }
1346 
1347  return;
1348 }
1349 
1360  vpColVector &position)
1361 {
1362  double timestamp;
1363  getPosition(frame, position, timestamp);
1364 }
1365 
1378  vpPoseVector &position,
1379  double &timestamp)
1380 {
1381  vpColVector posRxyz;
1382  //recupere position en Rxyz
1383  this->getPosition(frame, posRxyz, timestamp);
1384  vpRxyzVector RxyzVect;
1385  for (unsigned int j=0;j<3;j++)
1386  RxyzVect[j]=posRxyz[j+3];
1387  //recupere le vecteur thetaU correspondant
1388  vpThetaUVector RtuVect(RxyzVect);
1389 
1390  //remplit le vpPoseVector avec translation et rotation ThetaU
1391  for (unsigned int j=0;j<3;j++)
1392  {
1393  position[j]=posRxyz[j];
1394  position[j+3]=RtuVect[j];
1395  }
1396 }
1397 
1408  vpPoseVector &position)
1409 {
1410  double timestamp;
1411  getPosition(frame, position, timestamp);
1412 }
1413 
1418 {
1419  double timestamp;
1420  PrimitiveACQ_TIME_Viper650(&timestamp);
1421  return timestamp;
1422 }
1423 
1496 void
1498  const vpColVector & vel)
1499 {
1501  vpERROR_TRACE ("Cannot send a velocity to the robot "
1502  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1504  "Cannot send a velocity to the robot "
1505  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1506  }
1507 
1508  vpColVector vel_sat(6);
1509 
1510  // Velocity saturation
1511  switch(frame) {
1512  // saturation in cartesian space
1513  case vpRobot::CAMERA_FRAME :
1515  case vpRobot::MIXT_FRAME : {
1516  vpColVector vel_max(6);
1517 
1518  for (unsigned int i=0; i<3; i++)
1519  vel_max[i] = getMaxTranslationVelocity();
1520  for (unsigned int i=3; i<6; i++)
1521  vel_max[i] = getMaxRotationVelocity();
1522 
1523  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1524 
1525  break;
1526  }
1527  // saturation in joint space
1528  case vpRobot::ARTICULAR_FRAME : {
1529  vpColVector vel_max(6);
1530 
1532  for (unsigned int i=0; i<6; i++)
1533  vel_max[i] = getMaxRotationVelocity();
1534  }
1535  else {
1536  for (unsigned int i=0; i<5; i++)
1537  vel_max[i] = getMaxRotationVelocity();
1538  vel_max[5] = getMaxRotationVelocityJoint6();
1539  }
1540 
1541  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1542 
1543  }
1544  }
1545 
1546  InitTry;
1547 
1548  switch(frame) {
1549  case vpRobot::CAMERA_FRAME : {
1550  // Send velocities in m/s and rad/s
1551  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1552  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPCAM_VIPER650) );
1553  break ;
1554  }
1555  case vpRobot::ARTICULAR_FRAME : {
1556  // Convert all the velocities from rad/s into deg/s
1557  vel_sat.rad2deg();
1558  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1559  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER650) );
1560  Try( PrimitiveMOVESPEED_Viper650(vel_sat.data) );
1561  break ;
1562  }
1563  case vpRobot::REFERENCE_FRAME : {
1564  // Send velocities in m/s and rad/s
1565  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1566  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPFIX_VIPER650) );
1567  break ;
1568  }
1569  case vpRobot::MIXT_FRAME : {
1570  //Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPMIX_VIPER650) );
1571  break ;
1572  }
1573  default: {
1574  vpERROR_TRACE ("Error in spec of vpRobot. "
1575  "Case not taken in account.");
1576  return;
1577  }
1578  }
1579 
1580  Catch();
1581  if (TryStt < 0) {
1582  if (TryStt == VelStopOnJoint) {
1583  UInt32 axisInJoint[njoint];
1584  PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1585  for (unsigned int i=0; i < njoint; i ++) {
1586  if (axisInJoint[i])
1587  std::cout << "\nWarning: Velocity control stopped: axis "
1588  << i+1 << " on joint limit!" <<std::endl;
1589  }
1590  }
1591  else {
1592  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1593  if (TryString != NULL) {
1594  // The statement is in TryString, but we need to check the validity
1595  printf(" Error sentence %s\n", TryString); // Print the TryString
1596  }
1597  else {
1598  printf("\n");
1599  }
1600  }
1601  }
1602 
1603  return;
1604 }
1605 
1606 
1607 
1608 
1609 
1610 
1611 /* ------------------------------------------------------------------------ */
1612 /* --- GET ---------------------------------------------------------------- */
1613 /* ------------------------------------------------------------------------ */
1614 
1615 
1673  vpColVector & velocity, double &timestamp)
1674 {
1675  velocity.resize (6);
1676  velocity = 0;
1677 
1678  vpColVector q_cur(6);
1679  vpHomogeneousMatrix fMc_cur;
1680  vpHomogeneousMatrix cMc; // camera displacement
1681  double time_cur;
1682 
1683  InitTry;
1684 
1685  // Get the current joint position
1686  Try( PrimitiveACQ_POS_J_Viper650(q_cur.data, &timestamp) );
1687  time_cur = timestamp;
1688  q_cur.deg2rad();
1689 
1690  // Get the camera pose from the direct kinematics
1691  vpViper650::get_fMc(q_cur, fMc_cur);
1692 
1693  if ( ! first_time_getvel ) {
1694 
1695  switch (frame) {
1696  case vpRobot::CAMERA_FRAME: {
1697  // Compute the displacement of the camera since the previous call
1698  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1699 
1700  // Compute the velocity of the camera from this displacement
1701  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1702 
1703  break ;
1704  }
1705 
1706  case vpRobot::ARTICULAR_FRAME: {
1707  velocity = (q_cur - q_prev_getvel) / (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 vpRobotViper650::readPosFile(const char *filename, vpColVector &q)
1927 {
1928 
1929  FILE * fd ;
1930  fd = fopen(filename, "r") ;
1931  if (fd == NULL)
1932  return false;
1933 
1934  char line[FILENAME_MAX];
1935  char dummy[FILENAME_MAX];
1936  char head[] = "R:";
1937  bool sortie = false;
1938 
1939  do {
1940  // Saut des lignes commencant par #
1941  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1942  if ( strncmp (line, "#", 1) != 0) {
1943  // La ligne n'est pas un commentaire
1944  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1945  sortie = true; // Position robot trouvee.
1946  }
1947  // else
1948  // return (false); // fin fichier sans position robot.
1949  }
1950  }
1951  else {
1952  return (false); /* fin fichier */
1953  }
1954 
1955  }
1956  while ( sortie != true );
1957 
1958  // Lecture des positions
1959  q.resize(njoint);
1960  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1961  dummy,
1962  &q[0], &q[1], &q[2],
1963  &q[3], &q[4], &q[5]);
1964 
1965  // converts rotations from degrees into radians
1966  q.deg2rad();
1967 
1968  fclose(fd) ;
1969  return (true);
1970 }
1971 
1995 bool
1996  vpRobotViper650::savePosFile(const char *filename, const vpColVector &q)
1997 {
1998 
1999  FILE * fd ;
2000  fd = fopen(filename, "w") ;
2001  if (fd == NULL)
2002  return false;
2003 
2004  fprintf(fd, "\
2005 #Viper650 - Position - Version 1.00\n\
2006 #\n\
2007 # R: A B C D E F\n\
2008 # Joint position in degrees\n\
2009 #\n\
2010 #\n\n");
2011 
2012  // Save positions in mm and deg
2013  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2014  vpMath::deg(q[0]),
2015  vpMath::deg(q[1]),
2016  vpMath::deg(q[2]),
2017  vpMath::deg(q[3]),
2018  vpMath::deg(q[4]),
2019  vpMath::deg(q[5]));
2020 
2021  fclose(fd) ;
2022  return (true);
2023 }
2024 
2035 void
2036  vpRobotViper650::move(const char *filename)
2037 {
2038  vpColVector q;
2039 
2040  try {
2041  this->readPosFile(filename, q) ;
2043  this->setPositioningVelocity(10);
2045  }
2046  catch(...) {
2047  throw;
2048  }
2049 }
2050 
2064 void
2065  vpRobotViper650::getCameraDisplacement(vpColVector &displacement)
2066 {
2067  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2068 }
2080 void
2081  vpRobotViper650::getArticularDisplacement(vpColVector &displacement)
2082 {
2084 }
2085 
2106 void
2108  vpColVector &displacement)
2109 {
2110  displacement.resize (6);
2111  displacement = 0;
2112 
2113  double q[6];
2114  vpColVector q_cur(6);
2115  double timestamp;
2116 
2117  InitTry;
2118 
2119  // Get the current joint position
2120  Try( PrimitiveACQ_POS_Viper650(q, &timestamp) );
2121  for (unsigned int i=0; i < njoint; i ++) {
2122  q_cur[i] = q[i];
2123  }
2124 
2125  if ( ! first_time_getdis ) {
2126  switch (frame) {
2127  case vpRobot::CAMERA_FRAME: {
2128  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2129  return;
2130  break ;
2131  }
2132 
2133  case vpRobot::ARTICULAR_FRAME: {
2134  displacement = q_cur - q_prev_getdis;
2135  break ;
2136  }
2137 
2138  case vpRobot::REFERENCE_FRAME: {
2139  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2140  return;
2141  break ;
2142  }
2143 
2144  case vpRobot::MIXT_FRAME: {
2145  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2146  return;
2147  break ;
2148  }
2149  }
2150  }
2151  else {
2152  first_time_getdis = false;
2153  }
2154 
2155  // Memorize the joint position for the next call
2156  q_prev_getdis = q_cur;
2157 
2158  CatchPrint();
2159  if (TryStt < 0) {
2160  vpERROR_TRACE ("Cannot get velocity.");
2162  "Cannot get velocity.");
2163  }
2164 }
2165 
2179 void
2181 {
2182  InitTry;
2183 
2184  Try( PrimitiveTFS_BIAS_Viper650() );
2185 
2186  // Wait 500 ms to be sure the next measures take into account the bias
2187  vpTime::wait(500);
2188 
2189  CatchPrint();
2190  if (TryStt < 0) {
2191  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2193  "Cannot bias the force/torque sensor.");
2194  }
2195 }
2196 
2236 void
2238 {
2239  InitTry;
2240 
2241  H.resize (6);
2242 
2243  Try( PrimitiveTFS_ACQ_Viper650(H.data) );
2244 
2245  CatchPrint();
2246  if (TryStt < 0) {
2247  vpERROR_TRACE ("Cannot get the force/torque measures.");
2249  "Cannot get force/torque measures.");
2250  }
2251 }
2252 
2259 {
2260  InitTry;
2261  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
2262  std::cout << "Enable joint limits on axis 6..." << std::endl;
2263  CatchPrint();
2264  if (TryStt < 0) {
2265  vpERROR_TRACE ("Cannot enable joint limits on axis 6");
2267  "Cannot enable joint limits on axis 6.");
2268  }
2269 }
2270 
2281 {
2282  InitTry;
2283  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1) );
2284  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2285  CatchPrint();
2286  if (TryStt < 0) {
2287  vpERROR_TRACE ("Cannot disable joint limits on axis 6");
2289  "Cannot disable joint limits on axis 6.");
2290  }
2291 }
2292 
2300 void
2302 {
2305 
2306  return;
2307 }
2308 
2328 void
2330 {
2331  maxRotationVelocity_joint6 = w6_max;
2332  return;
2333 }
2334 
2341 double
2343 {
2344  return maxRotationVelocity_joint6;
2345 }
2346 
2347 #endif
2348 
static const double defaultPositioningVelocity
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.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
virtual ~vpRobotViper650(void)
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
#define vpERROR_TRACE
Definition: vpDebug.h: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 setMaxRotationVelocityJoint6(double w6_max)
Initialize the position controller.
Definition: vpRobot.h:71
class that defines a generic virtual robot
Definition: vpRobot.h:60
Automatic control mode (default).
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:167
void get_cVe(vpVelocityTwistMatrix &cVe) const
vpControlFrameType
Definition: vpRobot.h:78
vpRxyzVector erc
Definition: vpViper.h:149
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
static int wait(double t0, double t)
Definition: vpTime.cpp:149
void move(const char *filename)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:279
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:205
void deg2rad()
Definition: vpColVector.h:192
double getTime() const
The vpRotationMatrix considers the particular case of a rotation matrix.
double * data
address of the first element of the data array
Definition: vpMatrix.h:118
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper650.h:99
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Initialize the velocity controller.
Definition: vpRobot.h:70
Emergency stop activated.
vpRobotStateType
Definition: vpRobot.h:66
bool verbose_
Definition: vpRobot.h:115
vpTranslationVector etc
Definition: vpViper.h:148
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRowVector t() const
Transpose of a vector.
vpColVector joint_max
Definition: vpViper.h:160
Modelisation of the ADEPT Viper 650 robot.
Definition: vpViper650.h:66
void enableJoint6Limits() const
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:615
double getPositioningVelocity(void) const
Manual control mode activated when the dead man switch is in use.
void init(void)
Definition: vpViper650.cpp:175
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:91
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 get_fJe(vpMatrix &fJe)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1177
static bool savePosFile(const char *filename, const vpColVector &q)
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:266
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:931
static double deg(double rad)
Definition: vpMath.h:93
void biasForceTorqueSensor() const
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
static bool readPosFile(const char *filename, vpColVector &q)
The pose is a complete representation of every rigid motion in the euclidian space.
Definition: vpPoseVector.h:92
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:140
void disableJoint6Limits() const
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
void setMaxRotationVelocity(double w_max)
Class that consider the case of the Euler angles using the z-y-z convention, where are respectively...
Definition: vpRzyzVector.h:150
void setToolType(vpViper650::vpToolType tool)
Set the current tool type.
Definition: vpViper650.h:136
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void get_cMe(vpHomogeneousMatrix &cMe) 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 getForceTorque(vpColVector &H) const
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:143
void get_eJe(vpMatrix &eJe)
bool getPowerState() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:98
vpColVector joint_min
Definition: vpViper.h:161