Visual Servoing Platform  version 3.1.0
vpRobotViper850.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See http://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for the Irisa's Viper S850 robot.
33  *
34  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
39 #include <visp3/core/vpConfig.h>
40 
41 #ifdef VISP_HAVE_VIPER850
42 
43 #include <signal.h>
44 #include <stdlib.h>
45 #include <sys/types.h>
46 #include <unistd.h>
47 
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpExponentialMap.h>
50 #include <visp3/core/vpIoTools.h>
51 #include <visp3/core/vpThetaUVector.h>
52 #include <visp3/core/vpVelocityTwistMatrix.h>
53 #include <visp3/robot/vpRobot.h>
54 #include <visp3/robot/vpRobotException.h>
55 #include <visp3/robot/vpRobotViper850.h>
56 
57 /* ---------------------------------------------------------------------- */
58 /* --- STATIC ----------------------------------------------------------- */
59 /* ---------------------------------------------------------------------- */
60 
61 bool vpRobotViper850::robotAlreadyCreated = false;
62 
71 
72 /* ---------------------------------------------------------------------- */
73 /* --- EMERGENCY STOP --------------------------------------------------- */
74 /* ---------------------------------------------------------------------- */
75 
83 void emergencyStopViper850(int signo)
84 {
85  std::cout << "Stop the Viper850 application by signal (" << signo << "): " << (char)7;
86  switch (signo) {
87  case SIGINT:
88  std::cout << "SIGINT (stop by ^C) " << std::endl;
89  break;
90  case SIGBUS:
91  std::cout << "SIGBUS (stop due to a bus error) " << std::endl;
92  break;
93  case SIGSEGV:
94  std::cout << "SIGSEGV (stop due to a segmentation fault) " << std::endl;
95  break;
96  case SIGKILL:
97  std::cout << "SIGKILL (stop by CTRL \\) " << std::endl;
98  break;
99  case SIGQUIT:
100  std::cout << "SIGQUIT " << std::endl;
101  break;
102  default:
103  std::cout << signo << std::endl;
104  }
105  // std::cout << "Emergency stop called\n";
106  // PrimitiveESTOP_Viper850();
107  PrimitiveSTOP_Viper850();
108  std::cout << "Robot was stopped\n";
109 
110  // Free allocated resources
111  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
112 
113  fprintf(stdout, "Application ");
114  fflush(stdout);
115  kill(getpid(), SIGKILL);
116  exit(1);
117 }
118 
119 /* ---------------------------------------------------------------------- */
120 /* --- CONSTRUCTOR ------------------------------------------------------ */
121 /* ---------------------------------------------------------------------- */
122 
177 vpRobotViper850::vpRobotViper850(bool verbose) : vpViper850(), vpRobot()
178 {
179 
180  /*
181  #define SIGHUP 1 // hangup
182  #define SIGINT 2 // interrupt (rubout)
183  #define SIGQUIT 3 // quit (ASCII FS)
184  #define SIGILL 4 // illegal instruction (not reset when caught)
185  #define SIGTRAP 5 // trace trap (not reset when caught)
186  #define SIGIOT 6 // IOT instruction
187  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
188  #define SIGEMT 7 // EMT instruction
189  #define SIGFPE 8 // floating point exception
190  #define SIGKILL 9 // kill (cannot be caught or ignored)
191  #define SIGBUS 10 // bus error
192  #define SIGSEGV 11 // segmentation violation
193  #define SIGSYS 12 // bad argument to system call
194  #define SIGPIPE 13 // write on a pipe with no one to read it
195  #define SIGALRM 14 // alarm clock
196  #define SIGTERM 15 // software termination signal from kill
197  */
198 
199  signal(SIGINT, emergencyStopViper850);
200  signal(SIGBUS, emergencyStopViper850);
201  signal(SIGSEGV, emergencyStopViper850);
202  signal(SIGKILL, emergencyStopViper850);
203  signal(SIGQUIT, emergencyStopViper850);
204 
205  setVerbose(verbose);
206  if (verbose_)
207  std::cout << "Open communication with MotionBlox.\n";
208  try {
209  this->init();
211  } catch (...) {
212  // vpERROR_TRACE("Error caught") ;
213  throw;
214  }
215  positioningVelocity = defaultPositioningVelocity;
216 
217  maxRotationVelocity_joint6 = maxRotationVelocity;
218 
219  vpRobotViper850::robotAlreadyCreated = true;
220 
221  return;
222 }
223 
224 /* ------------------------------------------------------------------------ */
225 /* --- INITIALISATION ----------------------------------------------------- */
226 /* ------------------------------------------------------------------------ */
227 
253 {
254  InitTry;
255 
256  // Initialise private variables used to compute the measured velocities
257  q_prev_getvel.resize(6);
258  q_prev_getvel = 0;
259  time_prev_getvel = 0;
260  first_time_getvel = true;
261 
262  // Initialise private variables used to compute the measured displacement
263  q_prev_getdis.resize(6);
264  q_prev_getdis = 0;
265  first_time_getdis = true;
266 
267 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
268  std::string calibfile;
269 #ifdef VISP_HAVE_VIPER850_DATA
270  calibfile = std::string(VISP_VIPER850_DATA_PATH) + std::string("/ati/FT17824.cal");
271  if (!vpIoTools::checkFilename(calibfile))
272  throw(vpException(vpException::ioError, "ATI F/T calib file \"%s\" doesn't exist", calibfile.c_str()));
273 #else
274  throw(vpException(vpException::ioError, "You don't have access to Viper850 "
275  "data to retrive ATI F/T calib "
276  "file"));
277 #endif
278  ati.setCalibrationFile(calibfile);
279  ati.open();
280 #endif
281 
282  // Initialize the firewire connection
283  Try(InitializeConnection(verbose_));
284 
285  // Connect to the servoboard using the servo board GUID
286  Try(InitializeNode_Viper850());
287 
288  Try(PrimitiveRESET_Viper850());
289 
290  // Enable the joint limits on axis 6
291  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
292 
293  // Update the eMc matrix in the low level controller
295 
296  // Look if the power is on or off
297  UInt32 HIPowerStatus;
298  UInt32 EStopStatus;
299  Try(PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus));
300  CAL_Wait(0.1);
301 
302  // Print the robot status
303  if (verbose_) {
304  std::cout << "Robot status: ";
305  switch (EStopStatus) {
306  case ESTOP_AUTO:
307  controlMode = AUTO;
308  if (HIPowerStatus == 0)
309  std::cout << "Power is OFF" << std::endl;
310  else
311  std::cout << "Power is ON" << std::endl;
312  break;
313 
314  case ESTOP_MANUAL:
315  controlMode = MANUAL;
316  if (HIPowerStatus == 0)
317  std::cout << "Power is OFF" << std::endl;
318  else
319  std::cout << "Power is ON" << std::endl;
320  break;
321  case ESTOP_ACTIVATED:
322  controlMode = ESTOP;
323  std::cout << "Emergency stop is activated" << std::endl;
324  break;
325  default:
326  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
327  std::cout << "You have to call Adept for maintenance..." << std::endl;
328  // Free allocated resources
329  }
330  std::cout << std::endl;
331  }
332  // get real joint min/max from the MotionBlox
333  Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
334  // Convert units from degrees to radians
335  joint_min.deg2rad();
336  joint_max.deg2rad();
337 
338  // for (unsigned int i=0; i < njoint; i++) {
339  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
340  // joint_max[i]);
341  // }
342 
343  // If an error occur in the low level controller, goto here
344  // CatchPrint();
345  Catch();
346 
347  // Test if an error occurs
348  if (TryStt == -20001)
349  printf("No connection detected. Check if the robot is powered on \n"
350  "and if the firewire link exist between the MotionBlox and this "
351  "computer.\n");
352  else if (TryStt == -675)
353  printf(" Timeout enabling power...\n");
354 
355  if (TryStt < 0) {
356  // Power off the robot
357  PrimitivePOWEROFF_Viper850();
358  // Free allocated resources
359  ShutDownConnection();
360 
361  std::cout << "Cannot open connection with the motionblox..." << std::endl;
362  throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with the motionblox");
363  }
364  return;
365 }
366 
425 {
426  // Read the robot constants from files
427  // - joint [min,max], coupl_56, long_56
428  // - camera extrinsic parameters relative to eMc
429  vpViper850::init(tool, projModel);
430 
431  InitTry;
432 
433  // get real joint min/max from the MotionBlox
434  Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
435  // Convert units from degrees to radians
436  joint_min.deg2rad();
437  joint_max.deg2rad();
438 
439  // for (unsigned int i=0; i < njoint; i++) {
440  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
441  // joint_max[i]);
442  // }
443 
444  // Set the camera constant (eMc pose) in the MotionBlox
445  double eMc_pose[6];
446  for (unsigned int i = 0; i < 3; i++) {
447  eMc_pose[i] = etc[i]; // translation in meters
448  eMc_pose[i + 3] = erc[i]; // rotation in rad
449  }
450  // Update the eMc pose in the low level controller
451  Try(PrimitiveCONST_Viper850(eMc_pose));
452 
453  CatchPrint();
454  return;
455 }
456 
507 void vpRobotViper850::init(vpViper850::vpToolType tool, const std::string &filename)
508 {
509  vpViper850::init(tool, filename);
510 
511  InitTry;
512 
513  // Get real joint min/max from the MotionBlox
514  Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
515  // Convert units from degrees to radians
516  joint_min.deg2rad();
517  joint_max.deg2rad();
518 
519  // for (unsigned int i=0; i < njoint; i++) {
520  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
521  // joint_max[i]);
522  // }
523 
524  // Set the camera constant (eMc pose) in the MotionBlox
525  double eMc_pose[6];
526  for (unsigned int i = 0; i < 3; i++) {
527  eMc_pose[i] = etc[i]; // translation in meters
528  eMc_pose[i + 3] = erc[i]; // rotation in rad
529  }
530  // Update the eMc pose in the low level controller
531  Try(PrimitiveCONST_Viper850(eMc_pose));
532 
533  CatchPrint();
534  return;
535 }
536 
574 {
575  vpViper850::init(tool, eMc_);
576 
577  InitTry;
578 
579  // Get real joint min/max from the MotionBlox
580  Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
581  // Convert units from degrees to radians
582  joint_min.deg2rad();
583  joint_max.deg2rad();
584 
585  // for (unsigned int i=0; i < njoint; i++) {
586  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
587  // joint_max[i]);
588  // }
589 
590  // Set the camera constant (eMc pose) in the MotionBlox
591  double eMc_pose[6];
592  for (unsigned int i = 0; i < 3; i++) {
593  eMc_pose[i] = etc[i]; // translation in meters
594  eMc_pose[i + 3] = erc[i]; // rotation in rad
595  }
596  // Update the eMc pose in the low level controller
597  Try(PrimitiveCONST_Viper850(eMc_pose));
598 
599  CatchPrint();
600  return;
601 }
602 
615 {
616  this->vpViper850::set_eMc(eMc_);
617 
618  InitTry;
619 
620  // Set the camera constant (eMc pose) in the MotionBlox
621  double eMc_pose[6];
622  for (unsigned int i = 0; i < 3; i++) {
623  eMc_pose[i] = etc[i]; // translation in meters
624  eMc_pose[i + 3] = erc[i]; // rotation in rad
625  }
626  // Update the eMc pose in the low level controller
627  Try(PrimitiveCONST_Viper850(eMc_pose));
628 
629  CatchPrint();
630 
631  return;
632 }
633 
647 {
648  this->vpViper850::set_eMc(etc_, erc_);
649 
650  InitTry;
651 
652  // Set the camera constant (eMc pose) in the MotionBlox
653  double eMc_pose[6];
654  for (unsigned int i = 0; i < 3; i++) {
655  eMc_pose[i] = etc[i]; // translation in meters
656  eMc_pose[i + 3] = erc[i]; // rotation in rad
657  }
658  // Update the eMc pose in the low level controller
659  Try(PrimitiveCONST_Viper850(eMc_pose));
660 
661  CatchPrint();
662 
663  return;
664 }
665 
666 /* ------------------------------------------------------------------------ */
667 /* --- DESTRUCTOR --------------------------------------------------------- */
668 /* ------------------------------------------------------------------------ */
669 
677 {
678 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
679  ati.close();
680 #endif
681 
682  InitTry;
683 
685 
686  // Look if the power is on or off
687  UInt32 HIPowerStatus;
688  Try(PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus));
689  CAL_Wait(0.1);
690 
691  // if (HIPowerStatus == 1) {
692  // fprintf(stdout, "Power OFF the robot\n");
693  // fflush(stdout);
694 
695  // Try( PrimitivePOWEROFF_Viper850() );
696  // }
697 
698  // Free allocated resources
699  ShutDownConnection();
700 
701  vpRobotViper850::robotAlreadyCreated = false;
702 
703  CatchPrint();
704  return;
705 }
706 
714 {
715  InitTry;
716 
717  switch (newState) {
718  case vpRobot::STATE_STOP: {
719  // Start primitive STOP only if the current state is Velocity
721  Try(PrimitiveSTOP_Viper850());
722  vpTime::sleepMs(100); // needed to ensure velocity task ends up on low level
723  }
724  break;
725  }
728  std::cout << "Change the control mode from velocity to position control.\n";
729  Try(PrimitiveSTOP_Viper850());
730  } else {
731  // std::cout << "Change the control mode from stop to position
732  // control.\n";
733  }
734  this->powerOn();
735  break;
736  }
739  std::cout << "Change the control mode from stop to velocity control.\n";
740  }
741  this->powerOn();
742  break;
743  }
744  default:
745  break;
746  }
747 
748  CatchPrint();
749 
750  return vpRobot::setRobotState(newState);
751 }
752 
753 /* ------------------------------------------------------------------------ */
754 /* --- STOP --------------------------------------------------------------- */
755 /* ------------------------------------------------------------------------ */
756 
765 {
767  return;
768 
769  InitTry;
770  Try(PrimitiveSTOP_Viper850());
772 
773  CatchPrint();
774  if (TryStt < 0) {
775  vpERROR_TRACE("Cannot stop robot motion");
776  throw vpRobotException(vpRobotException::lowLevelError, "Cannot stop robot motion.");
777  }
778 }
779 
790 {
791  InitTry;
792 
793  // Look if the power is on or off
794  UInt32 HIPowerStatus;
795  UInt32 EStopStatus;
796  bool firsttime = true;
797  unsigned int nitermax = 10;
798 
799  for (unsigned int i = 0; i < nitermax; i++) {
800  Try(PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus));
801  if (EStopStatus == ESTOP_AUTO) {
802  controlMode = AUTO;
803  break; // exit for loop
804  } else if (EStopStatus == ESTOP_MANUAL) {
805  controlMode = MANUAL;
806  break; // exit for loop
807  } else if (EStopStatus == ESTOP_ACTIVATED) {
808  controlMode = ESTOP;
809  if (firsttime) {
810  std::cout << "Emergency stop is activated! \n"
811  << "Check the emergency stop button and push the yellow "
812  "button before continuing."
813  << std::endl;
814  firsttime = false;
815  }
816  fprintf(stdout, "Remaining time %us \r", nitermax - i);
817  fflush(stdout);
818  CAL_Wait(1);
819  } else {
820  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
821  std::cout << "You have to call Adept for maintenance..." << std::endl;
822  // Free allocated resources
823  ShutDownConnection();
824  exit(0);
825  }
826  }
827 
828  if (EStopStatus == ESTOP_ACTIVATED)
829  std::cout << std::endl;
830 
831  if (EStopStatus == ESTOP_ACTIVATED) {
832  std::cout << "Sorry, cannot power on the robot." << std::endl;
833  throw vpRobotException(vpRobotException::lowLevelError, "Cannot power on the robot.");
834  }
835 
836  if (HIPowerStatus == 0) {
837  fprintf(stdout, "Power ON the Viper850 robot\n");
838  fflush(stdout);
839 
840  Try(PrimitivePOWERON_Viper850());
841  }
842 
843  CatchPrint();
844  if (TryStt < 0) {
845  vpERROR_TRACE("Cannot power on the robot");
846  throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
847  }
848 }
849 
860 {
861  InitTry;
862 
863  // Look if the power is on or off
864  UInt32 HIPowerStatus;
865  Try(PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus));
866  CAL_Wait(0.1);
867 
868  if (HIPowerStatus == 1) {
869  fprintf(stdout, "Power OFF the Viper850 robot\n");
870  fflush(stdout);
871 
872  Try(PrimitivePOWEROFF_Viper850());
873  }
874 
875  CatchPrint();
876  if (TryStt < 0) {
877  vpERROR_TRACE("Cannot power off the robot");
878  throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
879  }
880 }
881 
894 {
895  InitTry;
896  bool status = false;
897  // Look if the power is on or off
898  UInt32 HIPowerStatus;
899  Try(PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus));
900  CAL_Wait(0.1);
901 
902  if (HIPowerStatus == 1) {
903  status = true;
904  }
905 
906  CatchPrint();
907  if (TryStt < 0) {
908  vpERROR_TRACE("Cannot get the power status");
909  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get the power status.");
910  }
911  return status;
912 }
913 
924 {
926  vpViper850::get_cMe(cMe);
927 
928  cVe.buildFrom(cMe);
929 }
930 
943 
956 {
957 
958  double position[6];
959  double timestamp;
960 
961  InitTry;
962  Try(PrimitiveACQ_POS_J_Viper850(position, &timestamp));
963  CatchPrint();
964 
965  vpColVector q(6);
966  for (unsigned int i = 0; i < njoint; i++)
967  q[i] = vpMath::rad(position[i]);
968 
969  try {
970  vpViper850::get_eJe(q, eJe);
971  } catch (...) {
972  vpERROR_TRACE("catch exception ");
973  throw;
974  }
975 }
989 {
990 
991  double position[6];
992  double timestamp;
993 
994  InitTry;
995  Try(PrimitiveACQ_POS_Viper850(position, &timestamp));
996  CatchPrint();
997 
998  vpColVector q(6);
999  for (unsigned int i = 0; i < njoint; i++)
1000  q[i] = position[i];
1001 
1002  try {
1003  vpViper850::get_fJe(q, fJe);
1004  } catch (...) {
1005  vpERROR_TRACE("Error caught");
1006  throw;
1007  }
1008 }
1009 
1047 void vpRobotViper850::setPositioningVelocity(const double velocity) { positioningVelocity = velocity; }
1048 
1054 double vpRobotViper850::getPositioningVelocity(void) const { return positioningVelocity; }
1055 
1135 {
1136 
1138  vpERROR_TRACE("Robot was not in position-based control\n"
1139  "Modification of the robot state");
1141  }
1142 
1143  vpColVector destination(njoint);
1144  int error = 0;
1145  double timestamp;
1146 
1147  InitTry;
1148  switch (frame) {
1149  case vpRobot::CAMERA_FRAME: {
1150  vpColVector q(njoint);
1151  Try(PrimitiveACQ_POS_Viper850(q.data, &timestamp));
1152 
1153  // Convert degrees into rad
1154  q.deg2rad();
1155 
1156  // Get fMc from the inverse kinematics
1157  vpHomogeneousMatrix fMc;
1158  vpViper850::get_fMc(q, fMc);
1159 
1160  // Set cMc from the input position
1161  vpTranslationVector txyz;
1162  vpRxyzVector rxyz;
1163  for (unsigned int i = 0; i < 3; i++) {
1164  txyz[i] = position[i];
1165  rxyz[i] = position[i + 3];
1166  }
1167 
1168  // Compute cMc2
1169  vpRotationMatrix cRc2(rxyz);
1170  vpHomogeneousMatrix cMc2(txyz, cRc2);
1171 
1172  // Compute the new position to reach: fMc*cMc2
1173  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1174 
1175  // Compute the corresponding joint position from the inverse kinematics
1176  unsigned int solution = this->getInverseKinematics(fMc2, q);
1177  if (solution) { // Position is reachable
1178  destination = q;
1179  // convert rad to deg requested for the low level controller
1180  destination.rad2deg();
1181  Try(PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity));
1182  Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1183  } else {
1184  // Cartesian position is out of range
1185  error = -1;
1186  }
1187 
1188  break;
1189  }
1190  case vpRobot::ARTICULAR_FRAME: {
1191  destination = position;
1192  // convert rad to deg requested for the low level controller
1193  destination.rad2deg();
1194 
1195  // std::cout << "Joint destination (deg): " << destination.t() <<
1196  // std::endl;
1197  Try(PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity));
1198  Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1199  break;
1200  }
1201  case vpRobot::REFERENCE_FRAME: {
1202  // Convert angles from Rxyz representation to Rzyz representation
1203  vpRxyzVector rxyz(position[3], position[4], position[5]);
1204  vpRotationMatrix R(rxyz);
1205  vpRzyzVector rzyz(R);
1206 
1207  for (unsigned int i = 0; i < 3; i++) {
1208  destination[i] = position[i];
1209  destination[i + 3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1210  }
1211  int configuration = 0; // keep the actual configuration
1212 
1213  // std::cout << "Base frame destination Rzyz (deg): " << destination.t()
1214  // << std::endl;
1215  Try(PrimitiveMOVE_C_Viper850(destination.data, configuration, positioningVelocity));
1216  Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1217 
1218  break;
1219  }
1220  case vpRobot::MIXT_FRAME: {
1221  vpERROR_TRACE("Positionning error. Mixt frame not implemented");
1222  throw vpRobotException(vpRobotException::lowLevelError, "Positionning error: "
1223  "Mixt frame not implemented.");
1224  }
1225  }
1226 
1227  CatchPrint();
1228  if (TryStt == InvalidPosition || TryStt == -1023)
1229  std::cout << " : Position out of range.\n";
1230  else if (TryStt == -3019) {
1231  if (frame == vpRobot::ARTICULAR_FRAME)
1232  std::cout << " : Joint position out of range.\n";
1233  else
1234  std::cout << " : Cartesian position leads to a joint position out of "
1235  "range.\n";
1236  } else if (TryStt < 0)
1237  std::cout << " : Unknown error (see Fabien).\n";
1238  else if (error == -1)
1239  std::cout << "Position out of range.\n";
1240 
1241  if (TryStt < 0 || error < 0) {
1242  vpERROR_TRACE("Positionning error.");
1243  throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1244  }
1245 
1246  return;
1247 }
1248 
1314 void vpRobotViper850::setPosition(const vpRobot::vpControlFrameType frame, const double pos1, const double pos2,
1315  const double pos3, const double pos4, const double pos5, const double pos6)
1316 {
1317  try {
1318  vpColVector position(6);
1319  position[0] = pos1;
1320  position[1] = pos2;
1321  position[2] = pos3;
1322  position[3] = pos4;
1323  position[4] = pos5;
1324  position[5] = pos6;
1325 
1326  setPosition(frame, position);
1327  } catch (...) {
1328  vpERROR_TRACE("Error caught");
1329  throw;
1330  }
1331 }
1332 
1372 void vpRobotViper850::setPosition(const std::string &filename)
1373 {
1374  vpColVector q;
1375  bool ret;
1376 
1377  ret = this->readPosFile(filename, q);
1378 
1379  if (ret == false) {
1380  vpERROR_TRACE("Bad position in \"%s\"", filename.c_str());
1381  throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1382  }
1385 }
1386 
1455 void vpRobotViper850::getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp)
1456 {
1457 
1458  InitTry;
1459 
1460  position.resize(6);
1461 
1462  switch (frame) {
1463  case vpRobot::CAMERA_FRAME: {
1464  position = 0;
1465  return;
1466  }
1467  case vpRobot::ARTICULAR_FRAME: {
1468  Try(PrimitiveACQ_POS_J_Viper850(position.data, &timestamp));
1469  // vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1470  position.deg2rad();
1471 
1472  return;
1473  }
1474  case vpRobot::REFERENCE_FRAME: {
1475  Try(PrimitiveACQ_POS_C_Viper850(position.data, &timestamp));
1476  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1477  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1478  // Convert Euler Rzyz angles from deg to rad
1479  for (unsigned int i = 3; i < 6; i++)
1480  position[i] = vpMath::rad(position[i]);
1481  // Convert Rzyz angles into Rxyz representation
1482  vpRzyzVector rzyz(position[3], position[4], position[5]);
1483  vpRotationMatrix R(rzyz);
1484  vpRxyzVector rxyz(R);
1485 
1486  // Update the position using Rxyz representation
1487  for (unsigned int i = 0; i < 3; i++)
1488  position[i + 3] = rxyz[i];
1489  // vpCTRACE << "Cartesian position Rxyz (deg)"
1490  // << position[0] << " " << position[1] << " " << position[2] << " "
1491  // << vpMath::deg(position[3]) << " "
1492  // << vpMath::deg(position[4]) << " "
1493  // << vpMath::deg(position[5]) << std::endl;
1494 
1495  break;
1496  }
1497  case vpRobot::MIXT_FRAME: {
1498  vpERROR_TRACE("Cannot get position in mixt frame: not implemented");
1499  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
1500  "not implemented");
1501  }
1502  }
1503 
1504  CatchPrint();
1505  if (TryStt < 0) {
1506  vpERROR_TRACE("Cannot get position.");
1507  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position.");
1508  }
1509 
1510  return;
1511 }
1512 
1518 {
1519  double timestamp;
1520  PrimitiveACQ_TIME_Viper850(&timestamp);
1521  return timestamp;
1522 }
1523 
1535 {
1536  double timestamp;
1537  getPosition(frame, position, timestamp);
1538 }
1539 
1551 void vpRobotViper850::getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
1552 {
1553  vpColVector posRxyz;
1554  // recupere position en Rxyz
1555  this->getPosition(frame, posRxyz, timestamp);
1556  vpRxyzVector RxyzVect;
1557  for (unsigned int j = 0; j < 3; j++)
1558  RxyzVect[j] = posRxyz[j + 3];
1559  // recupere le vecteur thetaU correspondant
1560  vpThetaUVector RtuVect(RxyzVect);
1561 
1562  // remplit le vpPoseVector avec translation et rotation ThetaU
1563  for (unsigned int j = 0; j < 3; j++) {
1564  position[j] = posRxyz[j];
1565  position[j + 3] = RtuVect[j];
1566  }
1567 }
1568 
1580 {
1581  vpColVector posRxyz;
1582  double timestamp;
1583  // recupere position en Rxyz
1584  this->getPosition(frame, posRxyz, timestamp);
1585  vpRxyzVector RxyzVect;
1586  for (unsigned int j = 0; j < 3; j++)
1587  RxyzVect[j] = posRxyz[j + 3];
1588  // recupere le vecteur thetaU correspondant
1589  vpThetaUVector RtuVect(RxyzVect);
1590 
1591  // remplit le vpPoseVector avec translation et rotation ThetaU
1592  for (unsigned int j = 0; j < 3; j++) {
1593  position[j] = posRxyz[j];
1594  position[j + 3] = RtuVect[j];
1595  }
1596 }
1597 
1677 {
1679  vpERROR_TRACE("Cannot send a velocity to the robot "
1680  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1682  "Cannot send a velocity to the robot "
1683  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1684  }
1685 
1686  vpColVector vel_sat(6);
1687 
1688  // Velocity saturation
1689  switch (frame) {
1690  // saturation in cartesian space
1691  case vpRobot::CAMERA_FRAME:
1693  case vpRobot::MIXT_FRAME: {
1694  vpColVector vel_max(6);
1695 
1696  for (unsigned int i = 0; i < 3; i++)
1697  vel_max[i] = getMaxTranslationVelocity();
1698  for (unsigned int i = 3; i < 6; i++)
1699  vel_max[i] = getMaxRotationVelocity();
1700 
1701  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1702 
1703  break;
1704  }
1705  // saturation in joint space
1706  case vpRobot::ARTICULAR_FRAME: {
1707  vpColVector vel_max(6);
1708 
1709  // if (getMaxRotationVelocity() == getMaxRotationVelocityJoint6()) {
1710  if (std::fabs(getMaxRotationVelocity() - getMaxRotationVelocityJoint6()) < std::numeric_limits<double>::epsilon()) {
1711 
1712  for (unsigned int i = 0; i < 6; i++)
1713  vel_max[i] = getMaxRotationVelocity();
1714  } else {
1715  for (unsigned int i = 0; i < 5; i++)
1716  vel_max[i] = getMaxRotationVelocity();
1717  vel_max[5] = getMaxRotationVelocityJoint6();
1718  }
1719 
1720  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1721  }
1722  }
1723 
1724  InitTry;
1725 
1726  switch (frame) {
1727  case vpRobot::CAMERA_FRAME: {
1728  // Send velocities in m/s and rad/s
1729  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1730  Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPCAM_VIPER850));
1731  break;
1732  }
1733  case vpRobot::ARTICULAR_FRAME: {
1734  // Convert all the velocities from rad/s into deg/s
1735  vel_sat.rad2deg();
1736  // std::cout << "Vitesse appliquee: " << vel_sat.t();
1737  // Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER850) );
1738  Try(PrimitiveMOVESPEED_Viper850(vel_sat.data));
1739  break;
1740  }
1741  case vpRobot::REFERENCE_FRAME: {
1742  // Send velocities in m/s and rad/s
1743  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1744  Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPFIX_VIPER850));
1745  break;
1746  }
1747  case vpRobot::MIXT_FRAME: {
1748  // Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPMIX_VIPER850) );
1749  break;
1750  }
1751  default: {
1752  vpERROR_TRACE("Error in spec of vpRobot. "
1753  "Case not taken in account.");
1754  return;
1755  }
1756  }
1757 
1758  Catch();
1759  if (TryStt < 0) {
1760  if (TryStt == VelStopOnJoint) {
1761  UInt32 axisInJoint[njoint];
1762  PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1763  for (unsigned int i = 0; i < njoint; i++) {
1764  if (axisInJoint[i])
1765  std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl;
1766  }
1767  } else {
1768  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1769  if (TryString != NULL) {
1770  // The statement is in TryString, but we need to check the validity
1771  printf(" Error sentence %s\n", TryString); // Print the TryString
1772  } else {
1773  printf("\n");
1774  }
1775  }
1776  }
1777 
1778  return;
1779 }
1780 
1781 /* ------------------------------------------------------------------------ */
1782 /* --- GET ---------------------------------------------------------------- */
1783 /* ------------------------------------------------------------------------ */
1784 
1842 void vpRobotViper850::getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp)
1843 {
1844 
1845  velocity.resize(6);
1846  velocity = 0;
1847 
1848  vpColVector q_cur(6);
1849  vpHomogeneousMatrix fMc_cur;
1850  vpHomogeneousMatrix cMc; // camera displacement
1851  double time_cur;
1852 
1853  InitTry;
1854 
1855  // Get the current joint position
1856  Try(PrimitiveACQ_POS_J_Viper850(q_cur.data, &timestamp));
1857  time_cur = timestamp;
1858  q_cur.deg2rad();
1859 
1860  // Get the camera pose from the direct kinematics
1861  vpViper850::get_fMc(q_cur, fMc_cur);
1862 
1863  if (!first_time_getvel) {
1864 
1865  switch (frame) {
1866  case vpRobot::CAMERA_FRAME: {
1867  // Compute the displacement of the camera since the previous call
1868  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1869 
1870  // Compute the velocity of the camera from this displacement
1871  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1872 
1873  break;
1874  }
1875 
1876  case vpRobot::ARTICULAR_FRAME: {
1877  velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1878  break;
1879  }
1880 
1881  case vpRobot::REFERENCE_FRAME: {
1882  // Compute the displacement of the camera since the previous call
1883  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1884 
1885  // Compute the velocity of the camera from this displacement
1886  vpColVector v;
1887  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1888 
1889  // Express this velocity in the reference frame
1890  vpVelocityTwistMatrix fVc(fMc_cur);
1891  velocity = fVc * v;
1892 
1893  break;
1894  }
1895 
1896  case vpRobot::MIXT_FRAME: {
1897  // Compute the displacement of the camera since the previous call
1898  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1899 
1900  // Compute the ThetaU representation for the rotation
1901  vpRotationMatrix cRc;
1902  cMc.extract(cRc);
1903  vpThetaUVector thetaU;
1904  thetaU.buildFrom(cRc);
1905 
1906  for (unsigned int i = 0; i < 3; i++) {
1907  // Compute the translation displacement in the reference frame
1908  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1909  // Update the rotation displacement in the camera frame
1910  velocity[i + 3] = thetaU[i];
1911  }
1912 
1913  // Compute the velocity
1914  velocity /= (time_cur - time_prev_getvel);
1915  break;
1916  }
1917  }
1918  } else {
1919  first_time_getvel = false;
1920  }
1921 
1922  // Memorize the camera pose for the next call
1923  fMc_prev_getvel = fMc_cur;
1924 
1925  // Memorize the joint position for the next call
1926  q_prev_getvel = q_cur;
1927 
1928  // Memorize the time associated to the joint position for the next call
1929  time_prev_getvel = time_cur;
1930 
1931  CatchPrint();
1932  if (TryStt < 0) {
1933  vpERROR_TRACE("Cannot get velocity.");
1934  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
1935  }
1936 }
1937 
1947 {
1948  double timestamp;
1949  getVelocity(frame, velocity, timestamp);
1950 }
1951 
2003 {
2004  vpColVector velocity;
2005  getVelocity(frame, velocity, timestamp);
2006 
2007  return velocity;
2008 }
2009 
2019 {
2020  vpColVector velocity;
2021  double timestamp;
2022  getVelocity(frame, velocity, timestamp);
2023 
2024  return velocity;
2025 }
2026 
2093 bool vpRobotViper850::readPosFile(const std::string &filename, vpColVector &q)
2094 {
2095  std::ifstream fd(filename.c_str(), std::ios::in);
2096 
2097  if (!fd.is_open()) {
2098  return false;
2099  }
2100 
2101  std::string line;
2102  std::string key("R:");
2103  std::string id("#Viper850 - Position");
2104  bool pos_found = false;
2105  int lineNum = 0;
2106 
2107  q.resize(njoint);
2108 
2109  while (std::getline(fd, line)) {
2110  lineNum++;
2111  if (lineNum == 1) {
2112  if (!(line.compare(0, id.size(), id) == 0)) { // check if Viper850 position file
2113  std::cout << "Error: this position file " << filename << " is not for Viper850 robot" << std::endl;
2114  return false;
2115  }
2116  }
2117  if ((line.compare(0, 1, "#") == 0)) { // skip comment
2118  continue;
2119  }
2120  if ((line.compare(0, key.size(), key) == 0)) { // decode position
2121  // check if there are at least njoint values in the line
2122  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2123  if (chain.size() < njoint + 1) // try to split with tab separator
2124  chain = vpIoTools::splitChain(line, std::string("\t"));
2125  if (chain.size() < njoint + 1)
2126  continue;
2127 
2128  std::istringstream ss(line);
2129  std::string key_;
2130  ss >> key_;
2131  for (unsigned int i = 0; i < njoint; i++)
2132  ss >> q[i];
2133  pos_found = true;
2134  break;
2135  }
2136  }
2137 
2138  // converts rotations from degrees into radians
2139  q.deg2rad();
2140 
2141  fd.close();
2142 
2143  if (!pos_found) {
2144  std::cout << "Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2145  return false;
2146  }
2147 
2148  return true;
2149 }
2150 
2174 bool vpRobotViper850::savePosFile(const std::string &filename, const vpColVector &q)
2175 {
2176 
2177  FILE *fd;
2178  fd = fopen(filename.c_str(), "w");
2179  if (fd == NULL)
2180  return false;
2181 
2182  fprintf(fd, "\
2183 #Viper850 - Position - Version 1.00\n\
2184 #\n\
2185 # R: A B C D E F\n\
2186 # Joint position in degrees\n\
2187 #\n\
2188 #\n\n");
2189 
2190  // Save positions in mm and deg
2191  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
2192  vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]));
2193 
2194  fclose(fd);
2195  return (true);
2196 }
2197 
2208 void vpRobotViper850::move(const std::string &filename)
2209 {
2210  vpColVector q;
2211 
2212  try {
2213  this->readPosFile(filename, q);
2215  this->setPositioningVelocity(10);
2217  } catch (...) {
2218  throw;
2219  }
2220 }
2221 
2241 {
2242  displacement.resize(6);
2243  displacement = 0;
2244 
2245  double q[6];
2246  vpColVector q_cur(6);
2247  double timestamp;
2248 
2249  InitTry;
2250 
2251  // Get the current joint position
2252  Try(PrimitiveACQ_POS_Viper850(q, &timestamp));
2253  for (unsigned int i = 0; i < njoint; i++) {
2254  q_cur[i] = q[i];
2255  }
2256 
2257  if (!first_time_getdis) {
2258  switch (frame) {
2259  case vpRobot::CAMERA_FRAME: {
2260  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2261  return;
2262  }
2263 
2264  case vpRobot::ARTICULAR_FRAME: {
2265  displacement = q_cur - q_prev_getdis;
2266  break;
2267  }
2268 
2269  case vpRobot::REFERENCE_FRAME: {
2270  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2271  return;
2272  }
2273 
2274  case vpRobot::MIXT_FRAME: {
2275  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2276  return;
2277  }
2278  }
2279  } else {
2280  first_time_getdis = false;
2281  }
2282 
2283  // Memorize the joint position for the next call
2284  q_prev_getdis = q_cur;
2285 
2286  CatchPrint();
2287  if (TryStt < 0) {
2288  vpERROR_TRACE("Cannot get velocity.");
2289  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
2290  }
2291 }
2292 
2301 {
2302 #if defined(USE_ATI_DAQ)
2303 #if defined(VISP_HAVE_COMEDI)
2304  ati.bias();
2305 #else
2306  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2307  "apt-get install libcomedi-dev"));
2308 #endif
2309 #else // Use serial link
2310  InitTry;
2311 
2312  Try(PrimitiveTFS_BIAS_Viper850());
2313 
2314  // Wait 500 ms to be sure the next measures take into account the bias
2315  vpTime::wait(500);
2316 
2317  CatchPrint();
2318  if (TryStt < 0) {
2319  vpERROR_TRACE("Cannot bias the force/torque sensor.");
2320  throw vpRobotException(vpRobotException::lowLevelError, "Cannot bias the force/torque sensor.");
2321  }
2322 #endif
2323 }
2324 
2333 {
2334 #if defined(USE_ATI_DAQ)
2335 #if defined(VISP_HAVE_COMEDI)
2336  ati.unbias();
2337 #else
2338  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2339  "apt-get install libcomedi-dev"));
2340 #endif
2341 #else // Use serial link
2342 // Not implemented
2343 #endif
2344 }
2345 
2387 {
2388 #if defined(USE_ATI_DAQ)
2389 #if defined(VISP_HAVE_COMEDI)
2390  H = ati.getForceTorque();
2391 #else
2392  (void)H;
2393  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2394  "apt-get install libcomedi-dev"));
2395 #endif
2396 #else // Use serial link
2397  InitTry;
2398 
2399  H.resize(6);
2400 
2401  Try(PrimitiveTFS_ACQ_Viper850(H.data));
2402 
2403  CatchPrint();
2404  if (TryStt < 0) {
2405  vpERROR_TRACE("Cannot get the force/torque measures.");
2406  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2407  }
2408 #endif
2409 }
2410 
2450 {
2451 #if defined(USE_ATI_DAQ)
2452 #if defined(VISP_HAVE_COMEDI)
2453  vpColVector H = ati.getForceTorque();
2454  return H;
2455 #else
2456  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2457  "apt-get install libcomedi-dev"));
2458 #endif
2459 #else // Use serial link
2460  InitTry;
2461 
2462  vpColVector H(6);
2463 
2464  Try(PrimitiveTFS_ACQ_Viper850(H.data));
2465  return H;
2466 
2467  CatchPrint();
2468  if (TryStt < 0) {
2469  vpERROR_TRACE("Cannot get the force/torque measures.");
2470  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2471  }
2472  return H; // Here to avoid a warning, but should never be called
2473 #endif
2474 }
2475 
2483 {
2484  InitTry;
2485  Try(PrimitivePneumaticGripper_Viper850(1));
2486  std::cout << "Open the pneumatic gripper..." << std::endl;
2487  CatchPrint();
2488  if (TryStt < 0) {
2489  throw vpRobotException(vpRobotException::lowLevelError, "Cannot open the gripper.");
2490  }
2491 }
2492 
2501 {
2502  InitTry;
2503  Try(PrimitivePneumaticGripper_Viper850(0));
2504  std::cout << "Close the pneumatic gripper..." << std::endl;
2505  CatchPrint();
2506  if (TryStt < 0) {
2507  throw vpRobotException(vpRobotException::lowLevelError, "Cannot close the gripper.");
2508  }
2509 }
2510 
2517 {
2518  InitTry;
2519  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
2520  std::cout << "Enable joint limits on axis 6..." << std::endl;
2521  CatchPrint();
2522  if (TryStt < 0) {
2523  vpERROR_TRACE("Cannot enable joint limits on axis 6");
2524  throw vpRobotException(vpRobotException::lowLevelError, "Cannot enable joint limits on axis 6.");
2525  }
2526 }
2527 
2539 {
2540  InitTry;
2541  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1));
2542  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2543  CatchPrint();
2544  if (TryStt < 0) {
2545  vpERROR_TRACE("Cannot disable joint limits on axis 6");
2546  throw vpRobotException(vpRobotException::lowLevelError, "Cannot disable joint limits on axis 6.");
2547  }
2548 }
2549 
2559 {
2562 
2563  return;
2564 }
2565 
2587 {
2588  maxRotationVelocity_joint6 = w6_max;
2589  return;
2590 }
2591 
2599 double vpRobotViper850::getMaxRotationVelocityJoint6() const { return maxRotationVelocity_joint6; }
2600 
2601 #elif !defined(VISP_BUILD_SHARED_LIBS)
2602 // Work arround to avoid warning: libvisp_robot.a(vpRobotViper850.cpp.o) has
2603 // no symbols
2604 void dummy_vpRobotViper850(){};
2605 #endif
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocity(double w_max)
void set_eMc(const vpHomogeneousMatrix &eMc_)
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:104
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:150
double getMaxRotationVelocityJoint6() const
Error that can be emited by the vpRobot class and its derivates.
void disableJoint6Limits() const
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1159
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:137
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
Definition: vpRobot.h:154
#define vpERROR_TRACE
Definition: vpDebug.h:393
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:251
void setPositioningVelocity(const double velocity)
vpColVector getForceTorque() const
double maxRotationVelocity
Definition: vpRobot.h:93
Initialize the position controller.
Definition: vpRobot.h:68
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
error that can be emited by ViSP classes.
Definition: vpException.h:71
vpHomogeneousMatrix inverse() const
vpRowVector t() const
Class that defines a generic virtual robot.
Definition: vpRobot.h:58
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:84
vpControlFrameType
Definition: vpRobot.h:75
vpRxyzVector erc
Definition: vpViper.h:160
void move(const std::string &filename)
void get_eJe(vpMatrix &eJe)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:273
void extract(vpRotationMatrix &R) const
double getTime() const
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
void enableJoint6Limits() const
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
void deg2rad()
Definition: vpColVector.h:134
Implementation of a rotation matrix and operations on such kind of matrices.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:600
static bool checkFilename(const char *filename)
Definition: vpIoTools.cpp:573
vpColVector getForceTorque() const
double getPositioningVelocity(void) const
Initialize the velocity controller.
Definition: vpRobot.h:67
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:139
vpRobotStateType
Definition: vpRobot.h:64
bool verbose_
Definition: vpRobot.h:111
vpTranslationVector etc
Definition: vpViper.h:159
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1230
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpColVector joint_max
Definition: vpViper.h:172
VISP_EXPORT void sleepMs(double t)
Definition: vpTime.cpp:258
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:128
Modelisation of the ADEPT Viper 850 robot.
Definition: vpViper850.h:103
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:563
bool getPowerState() const
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1665
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:922
void get_fJe(vpMatrix &fJe)
static double rad(double deg)
Definition: vpMath.h:102
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
static bool readPosFile(const std::string &filename, vpColVector &q)
static bool savePosFile(const std::string &filename, const vpColVector &q)
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:260
void get_cMe(vpHomogeneousMatrix &cMe) const
void get_cVe(vpVelocityTwistMatrix &cVe) const
void setMaxRotationVelocityJoint6(double w6_max)
static double deg(double rad)
Definition: vpMath.h:95
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition: vpRobot.h:99
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
static const double defaultPositioningVelocity
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:92
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:156
Emergency stop activated.
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper850.h:177
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRzyzVector.h:154
virtual ~vpRobotViper850(void)
void init(void)
Definition: vpViper850.cpp:136
void setCalibrationFile(const std::string &calibfile, unsigned short index=1)
Automatic control mode (default).
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:103
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void rad2deg()
Definition: vpColVector.h:225
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:154
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:970
void closeGripper() const
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:241
vpColVector joint_min
Definition: vpViper.h:173