ViSP  2.8.0
vpRobotViper850.cpp
1 /****************************************************************************
2  *
3  * $Id: vpRobotViper850.cpp 4218 2013-04-17 09:55:47Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2013 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Interface for the Irisa's Viper S850 robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
42 #include <visp/vpConfig.h>
43 
44 #ifdef VISP_HAVE_VIPER850
45 
46 #include <signal.h>
47 #include <stdlib.h>
48 #include <sys/types.h>
49 #include <unistd.h>
50 
51 #include <visp/vpRobotException.h>
52 #include <visp/vpExponentialMap.h>
53 #include <visp/vpDebug.h>
54 #include <visp/vpVelocityTwistMatrix.h>
55 #include <visp/vpThetaUVector.h>
56 #include <visp/vpRobot.h>
57 #include <visp/vpRobotViper850.h>
58 
59 /* ---------------------------------------------------------------------- */
60 /* --- STATIC ----------------------------------------------------------- */
61 /* ---------------------------------------------------------------------- */
62 
63 bool vpRobotViper850::robotAlreadyCreated = false;
64 
73 
74 /* ---------------------------------------------------------------------- */
75 /* --- EMERGENCY STOP --------------------------------------------------- */
76 /* ---------------------------------------------------------------------- */
77 
85 void emergencyStopViper850(int signo)
86 {
87  std::cout << "Stop the Viper850 application by signal ("
88  << signo << "): " << (char)7 ;
89  switch(signo)
90  {
91  case SIGINT:
92  std::cout << "SIGINT (stop by ^C) " << std::endl ; break ;
93  case SIGBUS:
94  std::cout <<"SIGBUS (stop due to a bus error) " << std::endl ; break ;
95  case SIGSEGV:
96  std::cout <<"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
97  case SIGKILL:
98  std::cout <<"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
99  case SIGQUIT:
100  std::cout <<"SIGQUIT " << std::endl ; break ;
101  default :
102  std::cout << signo << std::endl ;
103 }
104  //std::cout << "Emergency stop called\n";
105  // PrimitiveESTOP_Viper850();
106  PrimitiveSTOP_Viper850();
107  std::cout << "Robot was stopped\n";
108 
109  // Free allocated resources
110  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
111 
112  fprintf(stdout, "Application ");
113  fflush(stdout);
114  kill(getpid(), SIGKILL);
115  exit(1) ;
116 }
117 
118 /* ---------------------------------------------------------------------- */
119 /* --- CONSTRUCTOR ------------------------------------------------------ */
120 /* ---------------------------------------------------------------------- */
121 
177 vpRobotViper850::vpRobotViper850 (bool verbose)
178  :
179  vpViper850 (),
180  vpRobot ()
181 {
182 
183  /*
184  #define SIGHUP 1 // hangup
185  #define SIGINT 2 // interrupt (rubout)
186  #define SIGQUIT 3 // quit (ASCII FS)
187  #define SIGILL 4 // illegal instruction (not reset when caught)
188  #define SIGTRAP 5 // trace trap (not reset when caught)
189  #define SIGIOT 6 // IOT instruction
190  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
191  #define SIGEMT 7 // EMT instruction
192  #define SIGFPE 8 // floating point exception
193  #define SIGKILL 9 // kill (cannot be caught or ignored)
194  #define SIGBUS 10 // bus error
195  #define SIGSEGV 11 // segmentation violation
196  #define SIGSYS 12 // bad argument to system call
197  #define SIGPIPE 13 // write on a pipe with no one to read it
198  #define SIGALRM 14 // alarm clock
199  #define SIGTERM 15 // software termination signal from kill
200  */
201 
202  signal(SIGINT, emergencyStopViper850);
203  signal(SIGBUS, emergencyStopViper850) ;
204  signal(SIGSEGV, emergencyStopViper850) ;
205  signal(SIGKILL, emergencyStopViper850);
206  signal(SIGQUIT, emergencyStopViper850);
207 
208  setVerbose(verbose);
209  if (verbose_)
210  std::cout << "Open communication with MotionBlox.\n";
211  try {
212  this->init();
214  }
215  catch(...) {
216  // vpERROR_TRACE("Error caught") ;
217  throw ;
218  }
219  positioningVelocity = defaultPositioningVelocity ;
220 
221  vpRobotViper850::robotAlreadyCreated = true;
222 
223  return ;
224 }
225 
226 
227 /* ------------------------------------------------------------------------ */
228 /* --- INITIALISATION ----------------------------------------------------- */
229 /* ------------------------------------------------------------------------ */
230 
250 void
252 {
253  InitTry;
254 
255  // Initialise private variables used to compute the measured velocities
256  q_prev_getvel.resize(6);
257  q_prev_getvel = 0;
258  time_prev_getvel = 0;
259  first_time_getvel = true;
260 
261  // Initialise private variables used to compute the measured displacement
262  q_prev_getdis.resize(6);
263  q_prev_getdis = 0;
264  first_time_getdis = true;
265 
266 
267  // Initialize the firewire connection
268  Try( InitializeConnection(verbose_) );
269 
270  // Connect to the servoboard using the servo board GUID
271  Try( InitializeNode_Viper850() );
272 
273  Try( PrimitiveRESET_Viper850() );
274 
275  // Enable the joint limits on axis 6
276  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
277 
278  // Update the eMc matrix in the low level controller
280 
281  // Look if the power is on or off
282  UInt32 HIPowerStatus;
283  UInt32 EStopStatus;
284  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
285  &HIPowerStatus));
286  CAL_Wait(0.1);
287 
288  // Print the robot status
289  if (verbose_) {
290  std::cout << "Robot status: ";
291  switch(EStopStatus) {
292  case ESTOP_AUTO:
293  controlMode = AUTO;
294  if (HIPowerStatus == 0)
295  std::cout << "Power is OFF" << std::endl;
296  else
297  std::cout << "Power is ON" << std::endl;
298  break;
299 
300  case ESTOP_MANUAL:
301  controlMode = MANUAL;
302  if (HIPowerStatus == 0)
303  std::cout << "Power is OFF" << std::endl;
304  else
305  std::cout << "Power is ON" << std::endl;
306  break;
307  case ESTOP_ACTIVATED:
308  controlMode = ESTOP;
309  std::cout << "Emergency stop is activated" << std::endl;
310  break;
311  default:
312  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
313  std::cout << "You have to call Adept for maintenance..." << std::endl;
314  // Free allocated resources
315  }
316  std::cout << std::endl;
317  }
318  // get real joint min/max from the MotionBlox
319  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
320  // Convert units from degrees to radians
321  joint_min.deg2rad();
322  joint_max.deg2rad();
323 
324  // for (unsigned int i=0; i < njoint; i++) {
325  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
326  // }
327 
328  // If an error occur in the low level controller, goto here
329  //CatchPrint();
330  Catch();
331 
332  // Test if an error occurs
333  if (TryStt == -20001)
334  printf("No connection detected. Check if the robot is powered on \n"
335  "and if the firewire link exist between the MotionBlox and this computer.\n");
336  else if (TryStt == -675)
337  printf(" Timeout enabling power...\n");
338 
339  if (TryStt < 0) {
340  // Power off the robot
341  PrimitivePOWEROFF_Viper850();
342  // Free allocated resources
343  ShutDownConnection();
344 
345  std::cout << "Cannot open connexion with the motionblox..." << std::endl;
347  "Cannot open connexion with the motionblox");
348  }
349  return ;
350 }
351 
408 void
411 {
412 
413  InitTry;
414  // Read the robot constants from files
415  // - joint [min,max], coupl_56, long_56
416  // - camera extrinsic parameters relative to eMc
417  vpViper850::init(tool, projModel);
418 
419  // Set the camera constant (eMc pose) in the MotionBlox
420  double eMc_pose[6];
421  for (unsigned int i=0; i < 3; i ++) {
422  eMc_pose[i] = etc[i]; // translation in meters
423  eMc_pose[i+3] = erc[i]; // rotation in rad
424  }
425  // Update the eMc pose in the low level controller
426  Try( PrimitiveCONST_Viper850(eMc_pose) );
427 
428  // get real joint min/max from the MotionBlox
429  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
430  // Convert units from degrees to radians
431  joint_min.deg2rad();
432  joint_max.deg2rad();
433 
434  // for (unsigned int i=0; i < njoint; i++) {
435  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
436  // }
437 
438  setToolType(tool);
439 
440  CatchPrint();
441  return ;
442 }
443 
444 /* ------------------------------------------------------------------------ */
445 /* --- DESTRUCTOR --------------------------------------------------------- */
446 /* ------------------------------------------------------------------------ */
447 
455 {
456  InitTry;
457 
459 
460  // Look if the power is on or off
461  UInt32 HIPowerStatus;
462  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
463  &HIPowerStatus));
464  CAL_Wait(0.1);
465 
466  // if (HIPowerStatus == 1) {
467  // fprintf(stdout, "Power OFF the robot\n");
468  // fflush(stdout);
469 
470  // Try( PrimitivePOWEROFF_Viper850() );
471  // }
472 
473  // Free allocated resources
474  ShutDownConnection();
475 
476  vpRobotViper850::robotAlreadyCreated = false;
477 
478  CatchPrint();
479  return;
480 }
481 
482 
483 
484 
493 {
494  InitTry;
495 
496  switch (newState) {
497  case vpRobot::STATE_STOP: {
498  // Start primitive STOP only if the current state is Velocity
500  Try( PrimitiveSTOP_Viper850() );
501  }
502  break;
503  }
506  std::cout << "Change the control mode from velocity to position control.\n";
507  Try( PrimitiveSTOP_Viper850() );
508  }
509  else {
510  //std::cout << "Change the control mode from stop to position control.\n";
511  }
512  this->powerOn();
513  break;
514  }
517  std::cout << "Change the control mode from stop to velocity control.\n";
518  }
519  this->powerOn();
520  break;
521  }
522  default:
523  break ;
524  }
525 
526  CatchPrint();
527 
528  return vpRobot::setRobotState (newState);
529 }
530 
531 
532 /* ------------------------------------------------------------------------ */
533 /* --- STOP --------------------------------------------------------------- */
534 /* ------------------------------------------------------------------------ */
535 
543 void
545 {
547  return;
548 
549  InitTry;
550  Try( PrimitiveSTOP_Viper850() );
552 
553  CatchPrint();
554  if (TryStt < 0) {
555  vpERROR_TRACE ("Cannot stop robot motion");
557  "Cannot stop robot motion.");
558  }
559 }
560 
570 void
572 {
573  InitTry;
574 
575  // Look if the power is on or off
576  UInt32 HIPowerStatus;
577  UInt32 EStopStatus;
578  bool firsttime = true;
579  unsigned int nitermax = 10;
580 
581  for (unsigned int i=0; i<nitermax; i++) {
582  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
583  &HIPowerStatus));
584  if (EStopStatus == ESTOP_AUTO) {
585  controlMode = AUTO;
586  break; // exit for loop
587  }
588  else if (EStopStatus == ESTOP_MANUAL) {
589  controlMode = MANUAL;
590  break; // exit for loop
591  }
592  else if (EStopStatus == ESTOP_ACTIVATED) {
593  controlMode = ESTOP;
594  if (firsttime) {
595  std::cout << "Emergency stop is activated! \n"
596  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
597  firsttime = false;
598  }
599  fprintf(stdout, "Remaining time %ds \r", nitermax-i);
600  fflush(stdout);
601  CAL_Wait(1);
602  }
603  else {
604  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
605  std::cout << "You have to call Adept for maintenance..." << std::endl;
606  // Free allocated resources
607  ShutDownConnection();
608  exit(0);
609  }
610  }
611 
612  if (EStopStatus == ESTOP_ACTIVATED)
613  std::cout << std::endl;
614 
615  if (EStopStatus == ESTOP_ACTIVATED) {
616  std::cout << "Sorry, cannot power on the robot." << std::endl;
618  "Cannot power on the robot.");
619  }
620 
621  if (HIPowerStatus == 0) {
622  fprintf(stdout, "Power ON the Viper850 robot\n");
623  fflush(stdout);
624 
625  Try( PrimitivePOWERON_Viper850() );
626  }
627 
628  CatchPrint();
629  if (TryStt < 0) {
630  vpERROR_TRACE ("Cannot power on the robot");
632  "Cannot power off the robot.");
633  }
634 }
635 
645 void
647 {
648  InitTry;
649 
650  // Look if the power is on or off
651  UInt32 HIPowerStatus;
652  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
653  &HIPowerStatus));
654  CAL_Wait(0.1);
655 
656  if (HIPowerStatus == 1) {
657  fprintf(stdout, "Power OFF the Viper850 robot\n");
658  fflush(stdout);
659 
660  Try( PrimitivePOWEROFF_Viper850() );
661  }
662 
663  CatchPrint();
664  if (TryStt < 0) {
665  vpERROR_TRACE ("Cannot power off the robot");
667  "Cannot power off the robot.");
668  }
669 }
670 
682 bool
684 {
685  InitTry;
686  bool status = false;
687  // Look if the power is on or off
688  UInt32 HIPowerStatus;
689  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
690  &HIPowerStatus));
691  CAL_Wait(0.1);
692 
693  if (HIPowerStatus == 1) {
694  status = true;
695  }
696 
697  CatchPrint();
698  if (TryStt < 0) {
699  vpERROR_TRACE ("Cannot get the power status");
701  "Cannot get the power status.");
702  }
703  return status;
704 }
705 
715 void
717 {
718  vpHomogeneousMatrix cMe ;
719  vpViper850::get_cMe(cMe) ;
720 
721  cVe.buildFrom(cMe) ;
722 }
723 
735 void
737 {
738  vpViper850::get_cMe(cMe) ;
739 }
740 
741 
753 void
755 {
756 
757  double position[6];
758  double timestamp;
759 
760  InitTry;
761  Try( PrimitiveACQ_POS_J_Viper850(position, &timestamp) );
762  CatchPrint();
763 
764  vpColVector q(6);
765  for (unsigned int i=0; i < njoint; i++)
766  q[i] = vpMath::rad(position[i]);
767 
768  try
769  {
770  vpViper850::get_eJe(q, eJe) ;
771  }
772  catch(...)
773  {
774  vpERROR_TRACE("catch exception ") ;
775  throw ;
776  }
777 }
790 void
792 {
793 
794  double position[6];
795  double timestamp;
796 
797  InitTry;
798  Try( PrimitiveACQ_POS_Viper850(position, &timestamp) );
799  CatchPrint();
800 
801  vpColVector q(6);
802  for (unsigned int i=0; i < njoint; i++)
803  q[i] = position[i];
804 
805  try
806  {
807  vpViper850::get_fJe(q, fJe) ;
808  }
809  catch(...)
810  {
811  vpERROR_TRACE("Error caught");
812  throw ;
813  }
814 }
815 
853 void
855 {
856  positioningVelocity = velocity;
857 }
858 
864 double
866 {
867  return positioningVelocity;
868 }
869 
870 
948 void
950  const vpColVector & position )
951 {
952 
954  {
955  vpERROR_TRACE ("Robot was not in position-based control\n"
956  "Modification of the robot state");
958  }
959 
960  vpColVector destination(njoint);
961  int error = 0;
962  double timestamp;
963 
964  InitTry;
965  switch(frame) {
966  case vpRobot::CAMERA_FRAME : {
967  vpColVector q(njoint);
968  Try( PrimitiveACQ_POS_Viper850(q.data, &timestamp) );
969 
970  // Convert degrees into rad
971  q.deg2rad();
972 
973  // Get fMc from the inverse kinematics
975  vpViper850::get_fMc(q, fMc);
976 
977  // Set cMc from the input position
978  vpTranslationVector txyz;
979  vpRxyzVector rxyz;
980  for (unsigned int i=0; i < 3; i++) {
981  txyz[i] = position[i];
982  rxyz[i] = position[i+3];
983  }
984 
985  // Compute cMc2
986  vpRotationMatrix cRc2(rxyz);
987  vpHomogeneousMatrix cMc2(txyz, cRc2);
988 
989  // Compute the new position to reach: fMc*cMc2
990  vpHomogeneousMatrix fMc2 = fMc * cMc2;
991 
992  // Compute the corresponding joint position from the inverse kinematics
993  unsigned int solution = this->getInverseKinematics(fMc2, q);
994  if (solution) { // Position is reachable
995  destination = q;
996  // convert rad to deg requested for the low level controller
997  destination.rad2deg();
998  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
999  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1000  }
1001  else {
1002  // Cartesian position is out of range
1003  error = -1;
1004  }
1005 
1006  break ;
1007  }
1008  case vpRobot::ARTICULAR_FRAME: {
1009  destination = position;
1010  // convert rad to deg requested for the low level controller
1011  destination.rad2deg();
1012 
1013  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1014  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
1015  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1016  break ;
1017 
1018  }
1019  case vpRobot::REFERENCE_FRAME: {
1020  // Convert angles from Rxyz representation to Rzyz representation
1021  vpRxyzVector rxyz(position[3],position[4],position[5]);
1022  vpRotationMatrix R(rxyz);
1023  vpRzyzVector rzyz(R);
1024 
1025  for (unsigned int i=0; i <3; i++) {
1026  destination[i] = position[i];
1027  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1028  }
1029  int configuration = 0; // keep the actual configuration
1030 
1031  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1032  Try( PrimitiveMOVE_C_Viper850(destination.data, configuration,
1033  positioningVelocity) );
1034  Try( WaitState_Viper850(ETAT_ATTENTE_AFMA6, 1000) );
1035 
1036  break ;
1037  }
1038  case vpRobot::MIXT_FRAME:
1039  {
1040  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1042  "Positionning error: "
1043  "Mixt frame not implemented.");
1044  break ;
1045  }
1046  }
1047 
1048  CatchPrint();
1049  if (TryStt == InvalidPosition || TryStt == -1023)
1050  std::cout << " : Position out of range.\n";
1051  else if (TryStt == -3019) {
1052  if (frame == vpRobot::ARTICULAR_FRAME)
1053  std::cout << " : Joint position out of range.\n";
1054  else
1055  std::cout << " : Cartesian position leads to a joint position out of range.\n";
1056  }
1057  else if (TryStt < 0)
1058  std::cout << " : Unknown error (see Fabien).\n";
1059  else if (error == -1)
1060  std::cout << "Position out of range.\n";
1061 
1062  if (TryStt < 0 || error < 0) {
1063  vpERROR_TRACE ("Positionning error.");
1065  "Position out of range.");
1066  }
1067 
1068  return ;
1069 }
1070 
1137  const double pos1,
1138  const double pos2,
1139  const double pos3,
1140  const double pos4,
1141  const double pos5,
1142  const double pos6)
1143 {
1144  try{
1145  vpColVector position(6) ;
1146  position[0] = pos1 ;
1147  position[1] = pos2 ;
1148  position[2] = pos3 ;
1149  position[3] = pos4 ;
1150  position[4] = pos5 ;
1151  position[5] = pos6 ;
1152 
1153  setPosition(frame, position) ;
1154  }
1155  catch(...)
1156  {
1157  vpERROR_TRACE("Error caught");
1158  throw ;
1159  }
1160 }
1161 
1201 void vpRobotViper850::setPosition(const char *filename)
1202 {
1203  vpColVector q;
1204  bool ret;
1205 
1206  ret = this->readPosFile(filename, q);
1207 
1208  if (ret == false) {
1209  vpERROR_TRACE ("Bad position in \"%s\"", filename);
1211  "Bad position in filename.");
1212  }
1215 }
1216 
1286  vpColVector & position, double &timestamp)
1287 {
1288 
1289  InitTry;
1290 
1291  position.resize (6);
1292 
1293  switch (frame) {
1294  case vpRobot::CAMERA_FRAME : {
1295  position = 0;
1296  return;
1297  }
1298  case vpRobot::ARTICULAR_FRAME : {
1299  Try( PrimitiveACQ_POS_J_Viper850(position.data, &timestamp) );
1300  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1301  position.deg2rad();
1302 
1303  return;
1304  }
1305  case vpRobot::REFERENCE_FRAME : {
1306  Try( PrimitiveACQ_POS_C_Viper850(position.data, &timestamp) );
1307  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1308  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1309  // Convert Euler Rzyz angles from deg to rad
1310  for (unsigned int i=3; i <6; i++)
1311  position[i] = vpMath::rad(position[i]);
1312  // Convert Rzyz angles into Rxyz representation
1313  vpRzyzVector rzyz(position[3], position[4], position[5]);
1314  vpRotationMatrix R(rzyz);
1315  vpRxyzVector rxyz(R);
1316 
1317  // Update the position using Rxyz representation
1318  for (unsigned int i=0; i <3; i++)
1319  position[i+3] = rxyz[i];
1320  // vpCTRACE << "Cartesian position Rxyz (deg)"
1321  // << position[0] << " " << position[1] << " " << position[2] << " "
1322  // << vpMath::deg(position[3]) << " "
1323  // << vpMath::deg(position[4]) << " "
1324  // << vpMath::deg(position[5]) << std::endl;
1325 
1326  break ;
1327  }
1328  case vpRobot::MIXT_FRAME: {
1329  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1331  "Cannot get position in mixt frame: "
1332  "not implemented");
1333  break ;
1334  }
1335  }
1336 
1337  CatchPrint();
1338  if (TryStt < 0) {
1339  vpERROR_TRACE ("Cannot get position.");
1341  "Cannot get position.");
1342  }
1343 
1344  return;
1345 }
1346 
1351 {
1352  double timestamp;
1353  PrimitiveACQ_TIME_Viper850(&timestamp);
1354  return timestamp;
1355 }
1356 
1367  vpColVector & position)
1368 {
1369  double timestamp;
1370  getPosition(frame, position, timestamp);
1371 }
1372 
1384  vpPoseVector &position,
1385  double &timestamp)
1386 {
1387  vpColVector posRxyz;
1388  //recupere position en Rxyz
1389  this->getPosition(frame, posRxyz, timestamp);
1390  vpRxyzVector RxyzVect;
1391  for (unsigned int j=0;j<3;j++)
1392  RxyzVect[j]=posRxyz[j+3];
1393  //recupere le vecteur thetaU correspondant
1394  vpThetaUVector RtuVect(RxyzVect);
1395 
1396  //remplit le vpPoseVector avec translation et rotation ThetaU
1397  for (unsigned int j=0;j<3;j++)
1398  {
1399  position[j]=posRxyz[j];
1400  position[j+3]=RtuVect[j];
1401  }
1402 }
1403 
1414  vpPoseVector &position)
1415 {
1416  vpColVector posRxyz;
1417  double timestamp;
1418  //recupere position en Rxyz
1419  this->getPosition(frame, posRxyz, timestamp);
1420  vpRxyzVector RxyzVect;
1421  for (unsigned int j=0;j<3;j++)
1422  RxyzVect[j]=posRxyz[j+3];
1423  //recupere le vecteur thetaU correspondant
1424  vpThetaUVector RtuVect(RxyzVect);
1425 
1426  //remplit le vpPoseVector avec translation et rotation ThetaU
1427  for (unsigned int j=0;j<3;j++)
1428  {
1429  position[j]=posRxyz[j];
1430  position[j+3]=RtuVect[j];
1431  }
1432 }
1433 
1507  const vpColVector & vel)
1508 {
1510  vpERROR_TRACE ("Cannot send a velocity to the robot "
1511  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1513  "Cannot send a velocity to the robot "
1514  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1515  }
1516 
1517  vpColVector vel_sat(6);
1518 
1519  // Velocity saturation
1520  switch(frame) {
1521  // saturation in cartesian space
1522  case vpRobot::CAMERA_FRAME :
1524  case vpRobot::MIXT_FRAME : {
1525  vpColVector vel_max(6);
1526 
1527  for (unsigned int i=0; i<3; i++)
1528  vel_max[i] = getMaxTranslationVelocity();
1529  for (unsigned int i=3; i<6; i++)
1530  vel_max[i] = getMaxRotationVelocity();
1531 
1532  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1533 
1534  break;
1535  }
1536  // saturation in joint space
1537  case vpRobot::ARTICULAR_FRAME : {
1538  vpColVector vel_max(6);
1539 
1540  for (unsigned int i=0; i<6; i++)
1541  vel_max[i] = getMaxRotationVelocity();
1542 
1543  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1544  }
1545  }
1546 
1547  InitTry;
1548 
1549  switch(frame) {
1550  case vpRobot::CAMERA_FRAME : {
1551  // Send velocities in m/s and rad/s
1552  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1553  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPCAM_VIPER850) );
1554  break ;
1555  }
1556  case vpRobot::ARTICULAR_FRAME : {
1557  // Convert all the velocities from rad/s into deg/s
1558  vel_sat.rad2deg();
1559  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1560  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER850) );
1561  Try( PrimitiveMOVESPEED_Viper850(vel_sat.data) );
1562  break ;
1563  }
1564  case vpRobot::REFERENCE_FRAME : {
1565  // Send velocities in m/s and rad/s
1566  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1567  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPFIX_VIPER850) );
1568  break ;
1569  }
1570  case vpRobot::MIXT_FRAME : {
1571  //Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPMIX_VIPER850) );
1572  break ;
1573  }
1574  default: {
1575  vpERROR_TRACE ("Error in spec of vpRobot. "
1576  "Case not taken in account.");
1577  return;
1578  }
1579  }
1580 
1581  Catch();
1582  if (TryStt < 0) {
1583  if (TryStt == VelStopOnJoint) {
1584  UInt32 axisInJoint[njoint];
1585  PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1586  for (unsigned int i=0; i < njoint; i ++) {
1587  if (axisInJoint[i])
1588  std::cout << "\nWarning: Velocity control stopped: axis "
1589  << i+1 << " on joint limit!" <<std::endl;
1590  }
1591  }
1592  else {
1593  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1594  if (TryString != NULL) {
1595  // The statement is in TryString, but we need to check the validity
1596  printf(" Error sentence %s\n", TryString); // Print the TryString
1597  }
1598  else {
1599  printf("\n");
1600  }
1601  }
1602  }
1603 
1604  return;
1605 }
1606 
1607 
1608 
1609 
1610 
1611 
1612 /* ------------------------------------------------------------------------ */
1613 /* --- GET ---------------------------------------------------------------- */
1614 /* ------------------------------------------------------------------------ */
1615 
1616 
1674  vpColVector & velocity, double &timestamp)
1675 {
1676 
1677  velocity.resize (6);
1678  velocity = 0;
1679 
1680  vpColVector q_cur(6);
1681  vpHomogeneousMatrix fMc_cur;
1682  vpHomogeneousMatrix cMc; // camera displacement
1683  double time_cur;
1684 
1685  InitTry;
1686 
1687  // Get the current joint position
1688  Try( PrimitiveACQ_POS_J_Viper850(q_cur.data, &timestamp) );
1689  time_cur = timestamp;
1690  q_cur.deg2rad();
1691 
1692  // Get the camera pose from the direct kinematics
1693  vpViper850::get_fMc(q_cur, fMc_cur);
1694 
1695  if ( ! first_time_getvel ) {
1696 
1697  switch (frame) {
1698  case vpRobot::CAMERA_FRAME: {
1699  // Compute the displacement of the camera since the previous call
1700  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1701 
1702  // Compute the velocity of the camera from this displacement
1703  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1704 
1705  break ;
1706  }
1707 
1708  case vpRobot::ARTICULAR_FRAME: {
1709  velocity = (q_cur - q_prev_getvel)
1710  / (time_cur - time_prev_getvel);
1711  break ;
1712  }
1713 
1714  case vpRobot::REFERENCE_FRAME: {
1715  // Compute the displacement of the camera since the previous call
1716  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1717 
1718  // Compute the velocity of the camera from this displacement
1719  vpColVector v;
1720  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1721 
1722  // Express this velocity in the reference frame
1723  vpVelocityTwistMatrix fVc(fMc_cur);
1724  velocity = fVc * v;
1725 
1726  break ;
1727  }
1728 
1729  case vpRobot::MIXT_FRAME: {
1730  // Compute the displacement of the camera since the previous call
1731  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1732 
1733  // Compute the ThetaU representation for the rotation
1734  vpRotationMatrix cRc;
1735  cMc.extract(cRc);
1736  vpThetaUVector thetaU;
1737  thetaU.buildFrom(cRc);
1738 
1739  for (unsigned int i=0; i < 3; i++) {
1740  // Compute the translation displacement in the reference frame
1741  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1742  // Update the rotation displacement in the camera frame
1743  velocity[i+3] = thetaU[i];
1744  }
1745 
1746  // Compute the velocity
1747  velocity /= (time_cur - time_prev_getvel);
1748  break ;
1749  }
1750  }
1751  }
1752  else {
1753  first_time_getvel = false;
1754  }
1755 
1756  // Memorize the camera pose for the next call
1757  fMc_prev_getvel = fMc_cur;
1758 
1759  // Memorize the joint position for the next call
1760  q_prev_getvel = q_cur;
1761 
1762  // Memorize the time associated to the joint position for the next call
1763  time_prev_getvel = time_cur;
1764 
1765 
1766  CatchPrint();
1767  if (TryStt < 0) {
1768  vpERROR_TRACE ("Cannot get velocity.");
1770  "Cannot get velocity.");
1771  }
1772 }
1773 
1783  vpColVector & velocity)
1784 {
1785  double timestamp;
1786  getVelocity(frame, velocity, timestamp);
1787 }
1788 
1840 {
1841  vpColVector velocity;
1842  getVelocity (frame, velocity, timestamp);
1843 
1844  return velocity;
1845 }
1846 
1856 {
1857  vpColVector velocity;
1858  double timestamp;
1859  getVelocity (frame, velocity, timestamp);
1860 
1861  return velocity;
1862 }
1863 
1929 bool
1930  vpRobotViper850::readPosFile(const char *filename, vpColVector &q)
1931 {
1932 
1933  FILE * fd ;
1934  fd = fopen(filename, "r") ;
1935  if (fd == NULL)
1936  return false;
1937 
1938  char line[FILENAME_MAX];
1939  char dummy[FILENAME_MAX];
1940  char head[] = "R:";
1941  bool sortie = false;
1942 
1943  do {
1944  // Saut des lignes commencant par #
1945  if (fgets (line, FILENAME_MAX, fd) != NULL) {
1946  if ( strncmp (line, "#", 1) != 0) {
1947  // La ligne n'est pas un commentaire
1948  if ( strncmp (line, head, sizeof(head)-1) == 0) {
1949  sortie = true; // Position robot trouvee.
1950  }
1951  // else
1952  // return (false); // fin fichier sans position robot.
1953  }
1954  }
1955  else {
1956  return (false); /* fin fichier */
1957  }
1958 
1959  }
1960  while ( sortie != true );
1961 
1962  // Lecture des positions
1963  q.resize(njoint);
1964  sscanf(line, "%s %lf %lf %lf %lf %lf %lf",
1965  dummy,
1966  &q[0], &q[1], &q[2],
1967  &q[3], &q[4], &q[5]);
1968 
1969  // converts rotations from degrees into radians
1970  q.deg2rad();
1971 
1972  fclose(fd) ;
1973  return (true);
1974 }
1975 
1999 bool
2000  vpRobotViper850::savePosFile(const char *filename, const vpColVector &q)
2001 {
2002 
2003  FILE * fd ;
2004  fd = fopen(filename, "w") ;
2005  if (fd == NULL)
2006  return false;
2007 
2008  fprintf(fd, "\
2009 #Viper - Position - Version 1.0\n\
2010 #\n\
2011 # R: A B C D E F\n\
2012 # Joint position in degrees\n\
2013 #\n\
2014 #\n\n");
2015 
2016  // Save positions in mm and deg
2017  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2018  vpMath::deg(q[0]),
2019  vpMath::deg(q[1]),
2020  vpMath::deg(q[2]),
2021  vpMath::deg(q[3]),
2022  vpMath::deg(q[4]),
2023  vpMath::deg(q[5]));
2024 
2025  fclose(fd) ;
2026  return (true);
2027 }
2028 
2039 void
2040  vpRobotViper850::move(const char *filename)
2041 {
2042  vpColVector q;
2043 
2044  try {
2045  this->readPosFile(filename, q) ;
2047  this->setPositioningVelocity(10);
2049  }
2050  catch(...) {
2051  throw;
2052  }
2053 }
2054 
2068 void
2069  vpRobotViper850::getCameraDisplacement(vpColVector &displacement)
2070 {
2071  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2072 }
2084 void
2085  vpRobotViper850::getArticularDisplacement(vpColVector &displacement)
2086 {
2088 }
2089 
2110 void
2112  vpColVector &displacement)
2113 {
2114  displacement.resize (6);
2115  displacement = 0;
2116 
2117  double q[6];
2118  vpColVector q_cur(6);
2119  double timestamp;
2120 
2121  InitTry;
2122 
2123  // Get the current joint position
2124  Try( PrimitiveACQ_POS_Viper850(q, &timestamp) );
2125  for (unsigned int i=0; i < njoint; i ++) {
2126  q_cur[i] = q[i];
2127  }
2128 
2129  if ( ! first_time_getdis ) {
2130  switch (frame) {
2131  case vpRobot::CAMERA_FRAME: {
2132  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2133  return;
2134  break ;
2135  }
2136 
2137  case vpRobot::ARTICULAR_FRAME: {
2138  displacement = q_cur - q_prev_getdis;
2139  break ;
2140  }
2141 
2142  case vpRobot::REFERENCE_FRAME: {
2143  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2144  return;
2145  break ;
2146  }
2147 
2148  case vpRobot::MIXT_FRAME: {
2149  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2150  return;
2151  break ;
2152  }
2153  }
2154  }
2155  else {
2156  first_time_getdis = false;
2157  }
2158 
2159  // Memorize the joint position for the next call
2160  q_prev_getdis = q_cur;
2161 
2162  CatchPrint();
2163  if (TryStt < 0) {
2164  vpERROR_TRACE ("Cannot get velocity.");
2166  "Cannot get velocity.");
2167  }
2168 }
2169 
2183 void
2185 {
2186  InitTry;
2187 
2188  Try( PrimitiveTFS_BIAS_Viper850() );
2189 
2190  // Wait 500 ms to be sure the next measures take into account the bias
2191  vpTime::wait(500);
2192 
2193  CatchPrint();
2194  if (TryStt < 0) {
2195  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2197  "Cannot bias the force/torque sensor.");
2198  }
2199 }
2200 
2240 void
2242 {
2243  InitTry;
2244 
2245  H.resize (6);
2246 
2247  Try( PrimitiveTFS_ACQ_Viper850(H.data) );
2248 
2249  CatchPrint();
2250  if (TryStt < 0) {
2251  vpERROR_TRACE ("Cannot get the force/torque measures.");
2253  "Cannot get force/torque measures.");
2254  }
2255 }
2262 void
2264 {
2265  InitTry;
2266  Try( PrimitiveGripper_Viper850(1) );
2267  std::cout << "Open the gripper..." << std::endl;
2268  CatchPrint();
2269  if (TryStt < 0) {
2270  vpERROR_TRACE ("Cannot open the gripper");
2272  "Cannot open the gripper.");
2273  }
2274 }
2275 
2284 {
2285  InitTry;
2286  Try( PrimitiveGripper_Viper850(0) );
2287  std::cout << "Close the gripper..." << std::endl;
2288  CatchPrint();
2289  if (TryStt < 0) {
2290  vpERROR_TRACE ("Cannot close the gripper");
2292  "Cannot close the gripper.");
2293  }
2294 }
2295 
2302 {
2303  InitTry;
2304  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
2305  std::cout << "Enable joint limits on axis 6..." << std::endl;
2306  CatchPrint();
2307  if (TryStt < 0) {
2308  vpERROR_TRACE ("Cannot enable joint limits on axis 6");
2310  "Cannot enable joint limits on axis 6.");
2311  }
2312 }
2313 
2324 {
2325  InitTry;
2326  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1) );
2327  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2328  CatchPrint();
2329  if (TryStt < 0) {
2330  vpERROR_TRACE ("Cannot disable joint limits on axis 6");
2332  "Cannot disable joint limits on axis 6.");
2333  }
2334 }
2335 
2336 #endif
2337 
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
static vpColVector inverse(const vpHomogeneousMatrix &M)
Definition of the vpMatrix class.
Definition: vpMatrix.h:96
double getPositioningVelocity(void)
Error that can be emited by the vpRobot class and its derivates.
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:99
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
#define vpERROR_TRACE
Definition: vpDebug.h:379
void get_eJe(const vpColVector &q, vpMatrix &eJe)
Definition: vpViper.cpp:985
void setVerbose(bool verbose)
Definition: vpRobot.h:155
virtual vpRobotStateType getRobotState(void)
Definition: vpRobot.h:139
void setPositioningVelocity(const double velocity)
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:203
Initialize the position controller.
Definition: vpRobot.h:71
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
class that defines a generic virtual robot
Definition: vpRobot.h:60
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:116
vpControlFrameType
Definition: vpRobot.h:78
vpRxyzVector erc
Definition: vpViper.h:150
void get_eJe(vpMatrix &eJe)
static int wait(double t0, double t)
Definition: vpTime.cpp:149
static bool savePosFile(const char *filename, const vpColVector &q)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:228
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:154
void deg2rad()
Definition: vpColVector.h:187
The vpRotationMatrix considers the particular case of a rotation matrix.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
double * data
address of the first element of the data array
Definition: vpMatrix.h:116
static bool readPosFile(const char *filename, vpColVector &q)
Initialize the velocity controller.
Definition: vpRobot.h:70
vpRobotStateType
Definition: vpRobot.h:66
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
Definition: vpViper850.h:136
bool verbose_
Definition: vpRobot.h:115
vpTranslationVector etc
Definition: vpViper.h:149
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void getForceTorque(vpColVector &H)
vpRowVector t() const
transpose of Vector
vpColVector joint_max
Definition: vpViper.h:161
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:91
Modelisation of the ADEPT Viper 850 robot.
Definition: vpViper850.h:66
void extract(vpRotationMatrix &R) const
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
void get_fJe(vpMatrix &fJe)
static double rad(double deg)
Definition: vpMath.h:100
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpViper.cpp:1177
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
static double deg(double rad)
Definition: vpMath.h:93
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
Manual control mode activated when the dead man switch is in use.
static const double defaultPositioningVelocity
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
void get_cVe(vpVelocityTwistMatrix &cVe)
The pose is a complete representation of every rigid motion in the euclidian space.
Definition: vpPoseVector.h:92
vpHomogeneousMatrix inverse() const
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpViper.cpp:931
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
Definition: vpRxyzVector.h:152
Emergency stop activated.
Class that consider the case of the Euler angles using the z-y-z convention, where are respectively...
Definition: vpRzyzVector.h:150
virtual ~vpRobotViper850(void)
void init(void)
Definition: vpViper850.cpp:174
Automatic control mode (default).
double getTime() const
Class that consider the case of a translation vector.
Class that consider the case of the parameterization for the rotation.
void rad2deg()
Definition: vpColVector.h:177
void move(const char *filename)
void get_cMe(vpHomogeneousMatrix &cMe)
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false)
Definition: vpViper.cpp:576
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:144
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpViper.cpp:614
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:94
vpColVector joint_min
Definition: vpViper.h:162