Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
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
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Interface for the Irisa's Viper S850 robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #include <visp3/core/vpConfig.h>
39 
40 #ifdef VISP_HAVE_VIPER850
41 
42 #include <signal.h>
43 #include <stdlib.h>
44 #include <sys/types.h>
45 #include <unistd.h>
46 
47 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpExponentialMap.h>
49 #include <visp3/core/vpDebug.h>
50 #include <visp3/core/vpIoTools.h>
51 #include <visp3/core/vpVelocityTwistMatrix.h>
52 #include <visp3/core/vpThetaUVector.h>
53 #include <visp3/robot/vpRobot.h>
54 #include <visp3/robot/vpRobotViper850.h>
55 
56 /* ---------------------------------------------------------------------- */
57 /* --- STATIC ----------------------------------------------------------- */
58 /* ---------------------------------------------------------------------- */
59 
60 bool vpRobotViper850::robotAlreadyCreated = false;
61 
70 
71 /* ---------------------------------------------------------------------- */
72 /* --- EMERGENCY STOP --------------------------------------------------- */
73 /* ---------------------------------------------------------------------- */
74 
82 void emergencyStopViper850(int signo)
83 {
84  std::cout << "Stop the Viper850 application by signal ("
85  << signo << "): " << (char)7 ;
86  switch(signo)
87  {
88  case SIGINT:
89  std::cout << "SIGINT (stop by ^C) " << std::endl ; break ;
90  case SIGBUS:
91  std::cout <<"SIGBUS (stop due to a bus error) " << std::endl ; break ;
92  case SIGSEGV:
93  std::cout <<"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
94  case SIGKILL:
95  std::cout <<"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
96  case SIGQUIT:
97  std::cout <<"SIGQUIT " << std::endl ; break ;
98  default :
99  std::cout << signo << std::endl ;
100 }
101  //std::cout << "Emergency stop called\n";
102  // PrimitiveESTOP_Viper850();
103  PrimitiveSTOP_Viper850();
104  std::cout << "Robot was stopped\n";
105 
106  // Free allocated resources
107  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
108 
109  fprintf(stdout, "Application ");
110  fflush(stdout);
111  kill(getpid(), SIGKILL);
112  exit(1) ;
113 }
114 
115 /* ---------------------------------------------------------------------- */
116 /* --- CONSTRUCTOR ------------------------------------------------------ */
117 /* ---------------------------------------------------------------------- */
118 
174 vpRobotViper850::vpRobotViper850 (bool verbose)
175  :
176  vpViper850 (),
177  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  }
212  catch(...) {
213  // vpERROR_TRACE("Error caught") ;
214  throw ;
215  }
216  positioningVelocity = defaultPositioningVelocity ;
217 
218  maxRotationVelocity_joint6 = maxRotationVelocity;
219 
220  vpRobotViper850::robotAlreadyCreated = true;
221 
222  return ;
223 }
224 
225 
226 /* ------------------------------------------------------------------------ */
227 /* --- INITIALISATION ----------------------------------------------------- */
228 /* ------------------------------------------------------------------------ */
229 
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 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
269  std::string calibfile;
270 # ifdef VISP_HAVE_VIPER850_DATA
271  calibfile = std::string(VISP_VIPER850_DATA_PATH) + std::string("/ati/FT17824.cal");
272  if (! vpIoTools::checkFilename(calibfile))
273  throw(vpException(vpException::ioError, "ATI F/T calib file \"%s\" doesn't exist", calibfile.c_str()));
274 # else
275  throw(vpException(vpException::ioError, "You don't have access to Viper850 data to retrive ATI F/T calib file"));
276 # endif
277  ati.setCalibrationFile(calibfile);
278  ati.open();
279 #endif
280 
281  // Initialize the firewire connection
282  Try( InitializeConnection(verbose_) );
283 
284  // Connect to the servoboard using the servo board GUID
285  Try( InitializeNode_Viper850() );
286 
287  Try( PrimitiveRESET_Viper850() );
288 
289  // Enable the joint limits on axis 6
290  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
291 
292  // Update the eMc matrix in the low level controller
294 
295  // Look if the power is on or off
296  UInt32 HIPowerStatus;
297  UInt32 EStopStatus;
298  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
299  &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], joint_max[i]);
340  // }
341 
342  // If an error occur in the low level controller, goto here
343  //CatchPrint();
344  Catch();
345 
346  // Test if an error occurs
347  if (TryStt == -20001)
348  printf("No connection detected. Check if the robot is powered on \n"
349  "and if the firewire link exist between the MotionBlox and this computer.\n");
350  else if (TryStt == -675)
351  printf(" Timeout enabling power...\n");
352 
353  if (TryStt < 0) {
354  // Power off the robot
355  PrimitivePOWEROFF_Viper850();
356  // Free allocated resources
357  ShutDownConnection();
358 
359  std::cout << "Cannot open connection with the motionblox..." << std::endl;
361  "Cannot open connection with the motionblox");
362  }
363  return ;
364 }
365 
424 void
427 {
428  // Read the robot constants from files
429  // - joint [min,max], coupl_56, long_56
430  // - camera extrinsic parameters relative to eMc
431  vpViper850::init(tool, projModel);
432 
433  InitTry;
434 
435  // get real joint min/max from the MotionBlox
436  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
437  // Convert units from degrees to radians
438  joint_min.deg2rad();
439  joint_max.deg2rad();
440 
441  // for (unsigned int i=0; i < njoint; i++) {
442  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
443  // }
444 
445  // Set the camera constant (eMc pose) in the MotionBlox
446  double eMc_pose[6];
447  for (unsigned int i=0; i < 3; i ++) {
448  eMc_pose[i] = etc[i]; // translation in meters
449  eMc_pose[i+3] = erc[i]; // rotation in rad
450  }
451  // Update the eMc pose in the low level controller
452  Try( PrimitiveCONST_Viper850(eMc_pose) );
453 
454  CatchPrint();
455  return ;
456 }
457 
508 void
509 vpRobotViper850::init(vpViper850::vpToolType tool, const std::string &filename)
510 {
511  vpViper850::init(tool, filename);
512 
513  InitTry;
514 
515  // Get real joint min/max from the MotionBlox
516  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
517  // Convert units from degrees to radians
518  joint_min.deg2rad();
519  joint_max.deg2rad();
520 
521  // for (unsigned int i=0; i < njoint; i++) {
522  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
523  // }
524 
525  // Set the camera constant (eMc pose) in the MotionBlox
526  double eMc_pose[6];
527  for (unsigned int i=0; i < 3; i ++) {
528  eMc_pose[i] = etc[i]; // translation in meters
529  eMc_pose[i+3] = erc[i]; // rotation in rad
530  }
531  // Update the eMc pose in the low level controller
532  Try( PrimitiveCONST_Viper850(eMc_pose) );
533 
534  CatchPrint();
535  return ;
536 }
537 
574 void
576 {
577  vpViper850::init(tool, eMc_);
578 
579  InitTry;
580 
581  // Get real joint min/max from the MotionBlox
582  Try( PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data) );
583  // Convert units from degrees to radians
584  joint_min.deg2rad();
585  joint_max.deg2rad();
586 
587  // for (unsigned int i=0; i < njoint; i++) {
588  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
589  // }
590 
591  // Set the camera constant (eMc pose) in the MotionBlox
592  double eMc_pose[6];
593  for (unsigned int i=0; i < 3; i ++) {
594  eMc_pose[i] = etc[i]; // translation in meters
595  eMc_pose[i+3] = erc[i]; // rotation in rad
596  }
597  // Update the eMc pose in the low level controller
598  Try( PrimitiveCONST_Viper850(eMc_pose) );
599 
600  CatchPrint();
601  return ;
602 }
603 
615 void
617 {
618  this->vpViper850::set_eMc(eMc_);
619 
620  InitTry;
621 
622  // Set the camera constant (eMc pose) in the MotionBlox
623  double eMc_pose[6];
624  for (unsigned int i=0; i < 3; i ++) {
625  eMc_pose[i] = etc[i]; // translation in meters
626  eMc_pose[i+3] = erc[i]; // rotation in rad
627  }
628  // Update the eMc pose in the low level controller
629  Try( PrimitiveCONST_Viper850(eMc_pose) );
630 
631  CatchPrint();
632 
633  return ;
634 }
635 
648 void
650 {
651  this->vpViper850::set_eMc(etc_,erc_);
652 
653  InitTry;
654 
655  // Set the camera constant (eMc pose) in the MotionBlox
656  double eMc_pose[6];
657  for (unsigned int i=0; i < 3; i ++) {
658  eMc_pose[i] = etc[i]; // translation in meters
659  eMc_pose[i+3] = erc[i]; // rotation in rad
660  }
661  // Update the eMc pose in the low level controller
662  Try( PrimitiveCONST_Viper850(eMc_pose) );
663 
664  CatchPrint();
665 
666  return ;
667 }
668 
669 /* ------------------------------------------------------------------------ */
670 /* --- DESTRUCTOR --------------------------------------------------------- */
671 /* ------------------------------------------------------------------------ */
672 
680 {
681 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
682  ati.close();
683 #endif
684 
685  InitTry;
686 
688 
689  // Look if the power is on or off
690  UInt32 HIPowerStatus;
691  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
692  &HIPowerStatus));
693  CAL_Wait(0.1);
694 
695  // if (HIPowerStatus == 1) {
696  // fprintf(stdout, "Power OFF the robot\n");
697  // fflush(stdout);
698 
699  // Try( PrimitivePOWEROFF_Viper850() );
700  // }
701 
702  // Free allocated resources
703  ShutDownConnection();
704 
705  vpRobotViper850::robotAlreadyCreated = false;
706 
707  CatchPrint();
708  return;
709 }
710 
711 
712 
713 
722 {
723  InitTry;
724 
725  switch (newState) {
726  case vpRobot::STATE_STOP: {
727  // Start primitive STOP only if the current state is Velocity
729  Try( PrimitiveSTOP_Viper850() );
730  vpTime::sleepMs(100); // needed to ensure velocity task ends up on low level
731  }
732  break;
733  }
736  std::cout << "Change the control mode from velocity to position control.\n";
737  Try( PrimitiveSTOP_Viper850() );
738  }
739  else {
740  //std::cout << "Change the control mode from stop to position control.\n";
741  }
742  this->powerOn();
743  break;
744  }
747  std::cout << "Change the control mode from stop to velocity control.\n";
748  }
749  this->powerOn();
750  break;
751  }
752  default:
753  break ;
754  }
755 
756  CatchPrint();
757 
758  return vpRobot::setRobotState (newState);
759 }
760 
761 
762 /* ------------------------------------------------------------------------ */
763 /* --- STOP --------------------------------------------------------------- */
764 /* ------------------------------------------------------------------------ */
765 
773 void
775 {
777  return;
778 
779  InitTry;
780  Try( PrimitiveSTOP_Viper850() );
782 
783  CatchPrint();
784  if (TryStt < 0) {
785  vpERROR_TRACE ("Cannot stop robot motion");
787  "Cannot stop robot motion.");
788  }
789 }
790 
800 void
802 {
803  InitTry;
804 
805  // Look if the power is on or off
806  UInt32 HIPowerStatus;
807  UInt32 EStopStatus;
808  bool firsttime = true;
809  unsigned int nitermax = 10;
810 
811  for (unsigned int i=0; i<nitermax; i++) {
812  Try( PrimitiveSTATUS_Viper850(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
813  &HIPowerStatus));
814  if (EStopStatus == ESTOP_AUTO) {
815  controlMode = AUTO;
816  break; // exit for loop
817  }
818  else if (EStopStatus == ESTOP_MANUAL) {
819  controlMode = MANUAL;
820  break; // exit for loop
821  }
822  else if (EStopStatus == ESTOP_ACTIVATED) {
823  controlMode = ESTOP;
824  if (firsttime) {
825  std::cout << "Emergency stop is activated! \n"
826  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
827  firsttime = false;
828  }
829  fprintf(stdout, "Remaining time %us \r", nitermax-i);
830  fflush(stdout);
831  CAL_Wait(1);
832  }
833  else {
834  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
835  std::cout << "You have to call Adept for maintenance..." << std::endl;
836  // Free allocated resources
837  ShutDownConnection();
838  exit(0);
839  }
840  }
841 
842  if (EStopStatus == ESTOP_ACTIVATED)
843  std::cout << std::endl;
844 
845  if (EStopStatus == ESTOP_ACTIVATED) {
846  std::cout << "Sorry, cannot power on the robot." << std::endl;
848  "Cannot power on the robot.");
849  }
850 
851  if (HIPowerStatus == 0) {
852  fprintf(stdout, "Power ON the Viper850 robot\n");
853  fflush(stdout);
854 
855  Try( PrimitivePOWERON_Viper850() );
856  }
857 
858  CatchPrint();
859  if (TryStt < 0) {
860  vpERROR_TRACE ("Cannot power on the robot");
862  "Cannot power off the robot.");
863  }
864 }
865 
875 void
877 {
878  InitTry;
879 
880  // Look if the power is on or off
881  UInt32 HIPowerStatus;
882  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
883  &HIPowerStatus));
884  CAL_Wait(0.1);
885 
886  if (HIPowerStatus == 1) {
887  fprintf(stdout, "Power OFF the Viper850 robot\n");
888  fflush(stdout);
889 
890  Try( PrimitivePOWEROFF_Viper850() );
891  }
892 
893  CatchPrint();
894  if (TryStt < 0) {
895  vpERROR_TRACE ("Cannot power off the robot");
897  "Cannot power off the robot.");
898  }
899 }
900 
912 bool
914 {
915  InitTry;
916  bool status = false;
917  // Look if the power is on or off
918  UInt32 HIPowerStatus;
919  Try( PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, NULL,
920  &HIPowerStatus));
921  CAL_Wait(0.1);
922 
923  if (HIPowerStatus == 1) {
924  status = true;
925  }
926 
927  CatchPrint();
928  if (TryStt < 0) {
929  vpERROR_TRACE ("Cannot get the power status");
931  "Cannot get the power status.");
932  }
933  return status;
934 }
935 
945 void
947 {
948  vpHomogeneousMatrix cMe ;
949  vpViper850::get_cMe(cMe) ;
950 
951  cVe.buildFrom(cMe) ;
952 }
953 
965 void
967 {
968  vpViper850::get_cMe(cMe) ;
969 }
970 
971 
983 void
985 {
986 
987  double position[6];
988  double timestamp;
989 
990  InitTry;
991  Try( PrimitiveACQ_POS_J_Viper850(position, &timestamp) );
992  CatchPrint();
993 
994  vpColVector q(6);
995  for (unsigned int i=0; i < njoint; i++)
996  q[i] = vpMath::rad(position[i]);
997 
998  try
999  {
1000  vpViper850::get_eJe(q, eJe) ;
1001  }
1002  catch(...)
1003  {
1004  vpERROR_TRACE("catch exception ") ;
1005  throw ;
1006  }
1007 }
1020 void
1022 {
1023 
1024  double position[6];
1025  double timestamp;
1026 
1027  InitTry;
1028  Try( PrimitiveACQ_POS_Viper850(position, &timestamp) );
1029  CatchPrint();
1030 
1031  vpColVector q(6);
1032  for (unsigned int i=0; i < njoint; i++)
1033  q[i] = position[i];
1034 
1035  try
1036  {
1037  vpViper850::get_fJe(q, fJe) ;
1038  }
1039  catch(...)
1040  {
1041  vpERROR_TRACE("Error caught");
1042  throw ;
1043  }
1044 }
1045 
1083 void
1085 {
1086  positioningVelocity = velocity;
1087 }
1088 
1094 double
1096 {
1097  return positioningVelocity;
1098 }
1099 
1100 
1178 void
1180  const vpColVector & position )
1181 {
1182 
1184  {
1185  vpERROR_TRACE ("Robot was not in position-based control\n"
1186  "Modification of the robot state");
1188  }
1189 
1190  vpColVector destination(njoint);
1191  int error = 0;
1192  double timestamp;
1193 
1194  InitTry;
1195  switch(frame) {
1196  case vpRobot::CAMERA_FRAME : {
1197  vpColVector q(njoint);
1198  Try( PrimitiveACQ_POS_Viper850(q.data, &timestamp) );
1199 
1200  // Convert degrees into rad
1201  q.deg2rad();
1202 
1203  // Get fMc from the inverse kinematics
1204  vpHomogeneousMatrix fMc;
1205  vpViper850::get_fMc(q, fMc);
1206 
1207  // Set cMc from the input position
1208  vpTranslationVector txyz;
1209  vpRxyzVector rxyz;
1210  for (unsigned int i=0; i < 3; i++) {
1211  txyz[i] = position[i];
1212  rxyz[i] = position[i+3];
1213  }
1214 
1215  // Compute cMc2
1216  vpRotationMatrix cRc2(rxyz);
1217  vpHomogeneousMatrix cMc2(txyz, cRc2);
1218 
1219  // Compute the new position to reach: fMc*cMc2
1220  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1221 
1222  // Compute the corresponding joint position from the inverse kinematics
1223  unsigned int solution = this->getInverseKinematics(fMc2, q);
1224  if (solution) { // Position is reachable
1225  destination = q;
1226  // convert rad to deg requested for the low level controller
1227  destination.rad2deg();
1228  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
1229  Try( WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000) );
1230  }
1231  else {
1232  // Cartesian position is out of range
1233  error = -1;
1234  }
1235 
1236  break ;
1237  }
1238  case vpRobot::ARTICULAR_FRAME: {
1239  destination = position;
1240  // convert rad to deg requested for the low level controller
1241  destination.rad2deg();
1242 
1243  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1244  Try( PrimitiveMOVE_J_Viper850(destination.data, positioningVelocity) );
1245  Try( WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000) );
1246  break ;
1247 
1248  }
1249  case vpRobot::REFERENCE_FRAME: {
1250  // Convert angles from Rxyz representation to Rzyz representation
1251  vpRxyzVector rxyz(position[3],position[4],position[5]);
1252  vpRotationMatrix R(rxyz);
1253  vpRzyzVector rzyz(R);
1254 
1255  for (unsigned int i=0; i <3; i++) {
1256  destination[i] = position[i];
1257  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1258  }
1259  int configuration = 0; // keep the actual configuration
1260 
1261  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1262  Try( PrimitiveMOVE_C_Viper850(destination.data, configuration,
1263  positioningVelocity) );
1264  Try( WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000) );
1265 
1266  break ;
1267  }
1268  case vpRobot::MIXT_FRAME:
1269  {
1270  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1272  "Positionning error: "
1273  "Mixt frame not implemented.");
1274  }
1275  }
1276 
1277  CatchPrint();
1278  if (TryStt == InvalidPosition || TryStt == -1023)
1279  std::cout << " : Position out of range.\n";
1280  else if (TryStt == -3019) {
1281  if (frame == vpRobot::ARTICULAR_FRAME)
1282  std::cout << " : Joint position out of range.\n";
1283  else
1284  std::cout << " : Cartesian position leads to a joint position out of range.\n";
1285  }
1286  else if (TryStt < 0)
1287  std::cout << " : Unknown error (see Fabien).\n";
1288  else if (error == -1)
1289  std::cout << "Position out of range.\n";
1290 
1291  if (TryStt < 0 || error < 0) {
1292  vpERROR_TRACE ("Positionning error.");
1294  "Position out of range.");
1295  }
1296 
1297  return ;
1298 }
1299 
1366  const double pos1,
1367  const double pos2,
1368  const double pos3,
1369  const double pos4,
1370  const double pos5,
1371  const double pos6)
1372 {
1373  try{
1374  vpColVector position(6) ;
1375  position[0] = pos1 ;
1376  position[1] = pos2 ;
1377  position[2] = pos3 ;
1378  position[3] = pos4 ;
1379  position[4] = pos5 ;
1380  position[5] = pos6 ;
1381 
1382  setPosition(frame, position) ;
1383  }
1384  catch(...)
1385  {
1386  vpERROR_TRACE("Error caught");
1387  throw ;
1388  }
1389 }
1390 
1430 void vpRobotViper850::setPosition(const std::string &filename)
1431 {
1432  vpColVector q;
1433  bool ret;
1434 
1435  ret = this->readPosFile(filename, q);
1436 
1437  if (ret == false) {
1438  vpERROR_TRACE ("Bad position in \"%s\"", filename.c_str());
1440  "Bad position in filename.");
1441  }
1444 }
1445 
1515  vpColVector & position, double &timestamp)
1516 {
1517 
1518  InitTry;
1519 
1520  position.resize (6);
1521 
1522  switch (frame) {
1523  case vpRobot::CAMERA_FRAME : {
1524  position = 0;
1525  return;
1526  }
1527  case vpRobot::ARTICULAR_FRAME : {
1528  Try( PrimitiveACQ_POS_J_Viper850(position.data, &timestamp) );
1529  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1530  position.deg2rad();
1531 
1532  return;
1533  }
1534  case vpRobot::REFERENCE_FRAME : {
1535  Try( PrimitiveACQ_POS_C_Viper850(position.data, &timestamp) );
1536  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1537  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1538  // Convert Euler Rzyz angles from deg to rad
1539  for (unsigned int i=3; i <6; i++)
1540  position[i] = vpMath::rad(position[i]);
1541  // Convert Rzyz angles into Rxyz representation
1542  vpRzyzVector rzyz(position[3], position[4], position[5]);
1543  vpRotationMatrix R(rzyz);
1544  vpRxyzVector rxyz(R);
1545 
1546  // Update the position using Rxyz representation
1547  for (unsigned int i=0; i <3; i++)
1548  position[i+3] = rxyz[i];
1549  // vpCTRACE << "Cartesian position Rxyz (deg)"
1550  // << position[0] << " " << position[1] << " " << position[2] << " "
1551  // << vpMath::deg(position[3]) << " "
1552  // << vpMath::deg(position[4]) << " "
1553  // << vpMath::deg(position[5]) << std::endl;
1554 
1555  break ;
1556  }
1557  case vpRobot::MIXT_FRAME: {
1558  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1560  "Cannot get position in mixt frame: "
1561  "not implemented");
1562  }
1563  }
1564 
1565  CatchPrint();
1566  if (TryStt < 0) {
1567  vpERROR_TRACE ("Cannot get position.");
1569  "Cannot get position.");
1570  }
1571 
1572  return;
1573 }
1574 
1579 {
1580  double timestamp;
1581  PrimitiveACQ_TIME_Viper850(&timestamp);
1582  return timestamp;
1583 }
1584 
1595  vpColVector & position)
1596 {
1597  double timestamp;
1598  getPosition(frame, position, timestamp);
1599 }
1600 
1612  vpPoseVector &position,
1613  double &timestamp)
1614 {
1615  vpColVector posRxyz;
1616  //recupere position en Rxyz
1617  this->getPosition(frame, posRxyz, timestamp);
1618  vpRxyzVector RxyzVect;
1619  for (unsigned int j=0;j<3;j++)
1620  RxyzVect[j]=posRxyz[j+3];
1621  //recupere le vecteur thetaU correspondant
1622  vpThetaUVector RtuVect(RxyzVect);
1623 
1624  //remplit le vpPoseVector avec translation et rotation ThetaU
1625  for (unsigned int j=0;j<3;j++)
1626  {
1627  position[j]=posRxyz[j];
1628  position[j+3]=RtuVect[j];
1629  }
1630 }
1631 
1642  vpPoseVector &position)
1643 {
1644  vpColVector posRxyz;
1645  double timestamp;
1646  //recupere position en Rxyz
1647  this->getPosition(frame, posRxyz, timestamp);
1648  vpRxyzVector RxyzVect;
1649  for (unsigned int j=0;j<3;j++)
1650  RxyzVect[j]=posRxyz[j+3];
1651  //recupere le vecteur thetaU correspondant
1652  vpThetaUVector RtuVect(RxyzVect);
1653 
1654  //remplit le vpPoseVector avec translation et rotation ThetaU
1655  for (unsigned int j=0;j<3;j++)
1656  {
1657  position[j]=posRxyz[j];
1658  position[j+3]=RtuVect[j];
1659  }
1660 }
1661 
1735  const vpColVector & vel)
1736 {
1738  vpERROR_TRACE ("Cannot send a velocity to the robot "
1739  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1741  "Cannot send a velocity to the robot "
1742  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1743  }
1744 
1745  vpColVector vel_sat(6);
1746 
1747  // Velocity saturation
1748  switch(frame) {
1749  // saturation in cartesian space
1750  case vpRobot::CAMERA_FRAME :
1752  case vpRobot::MIXT_FRAME : {
1753  vpColVector vel_max(6);
1754 
1755  for (unsigned int i=0; i<3; i++)
1756  vel_max[i] = getMaxTranslationVelocity();
1757  for (unsigned int i=3; i<6; i++)
1758  vel_max[i] = getMaxRotationVelocity();
1759 
1760  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1761 
1762  break;
1763  }
1764  // saturation in joint space
1765  case vpRobot::ARTICULAR_FRAME : {
1766  vpColVector vel_max(6);
1767 
1768  //if (getMaxRotationVelocity() == getMaxRotationVelocityJoint6()) {
1769  if (std::fabs(getMaxRotationVelocity() - getMaxRotationVelocityJoint6()) < std::numeric_limits<double>::epsilon()) {
1770 
1771  for (unsigned int i=0; i<6; i++)
1772  vel_max[i] = getMaxRotationVelocity();
1773  }
1774  else {
1775  for (unsigned int i=0; i<5; i++)
1776  vel_max[i] = getMaxRotationVelocity();
1777  vel_max[5] = getMaxRotationVelocityJoint6();
1778  }
1779 
1780  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1781  }
1782  }
1783 
1784  InitTry;
1785 
1786  switch(frame) {
1787  case vpRobot::CAMERA_FRAME : {
1788  // Send velocities in m/s and rad/s
1789  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1790  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPCAM_VIPER850) );
1791  break ;
1792  }
1793  case vpRobot::ARTICULAR_FRAME : {
1794  // Convert all the velocities from rad/s into deg/s
1795  vel_sat.rad2deg();
1796  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1797  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER850) );
1798  Try( PrimitiveMOVESPEED_Viper850(vel_sat.data) );
1799  break ;
1800  }
1801  case vpRobot::REFERENCE_FRAME : {
1802  // Send velocities in m/s and rad/s
1803  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1804  Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPFIX_VIPER850) );
1805  break ;
1806  }
1807  case vpRobot::MIXT_FRAME : {
1808  //Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPMIX_VIPER850) );
1809  break ;
1810  }
1811  default: {
1812  vpERROR_TRACE ("Error in spec of vpRobot. "
1813  "Case not taken in account.");
1814  return;
1815  }
1816  }
1817 
1818  Catch();
1819  if (TryStt < 0) {
1820  if (TryStt == VelStopOnJoint) {
1821  UInt32 axisInJoint[njoint];
1822  PrimitiveSTATUS_Viper850(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1823  for (unsigned int i=0; i < njoint; i ++) {
1824  if (axisInJoint[i])
1825  std::cout << "\nWarning: Velocity control stopped: axis "
1826  << i+1 << " on joint limit!" <<std::endl;
1827  }
1828  }
1829  else {
1830  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1831  if (TryString != NULL) {
1832  // The statement is in TryString, but we need to check the validity
1833  printf(" Error sentence %s\n", TryString); // Print the TryString
1834  }
1835  else {
1836  printf("\n");
1837  }
1838  }
1839  }
1840 
1841  return;
1842 }
1843 
1844 
1845 
1846 
1847 
1848 
1849 /* ------------------------------------------------------------------------ */
1850 /* --- GET ---------------------------------------------------------------- */
1851 /* ------------------------------------------------------------------------ */
1852 
1853 
1911  vpColVector & velocity, double &timestamp)
1912 {
1913 
1914  velocity.resize (6);
1915  velocity = 0;
1916 
1917  vpColVector q_cur(6);
1918  vpHomogeneousMatrix fMc_cur;
1919  vpHomogeneousMatrix cMc; // camera displacement
1920  double time_cur;
1921 
1922  InitTry;
1923 
1924  // Get the current joint position
1925  Try( PrimitiveACQ_POS_J_Viper850(q_cur.data, &timestamp) );
1926  time_cur = timestamp;
1927  q_cur.deg2rad();
1928 
1929  // Get the camera pose from the direct kinematics
1930  vpViper850::get_fMc(q_cur, fMc_cur);
1931 
1932  if ( ! first_time_getvel ) {
1933 
1934  switch (frame) {
1935  case vpRobot::CAMERA_FRAME: {
1936  // Compute the displacement of the camera since the previous call
1937  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1938 
1939  // Compute the velocity of the camera from this displacement
1940  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1941 
1942  break ;
1943  }
1944 
1945  case vpRobot::ARTICULAR_FRAME: {
1946  velocity = (q_cur - q_prev_getvel)
1947  / (time_cur - time_prev_getvel);
1948  break ;
1949  }
1950 
1951  case vpRobot::REFERENCE_FRAME: {
1952  // Compute the displacement of the camera since the previous call
1953  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1954 
1955  // Compute the velocity of the camera from this displacement
1956  vpColVector v;
1957  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1958 
1959  // Express this velocity in the reference frame
1960  vpVelocityTwistMatrix fVc(fMc_cur);
1961  velocity = fVc * v;
1962 
1963  break ;
1964  }
1965 
1966  case vpRobot::MIXT_FRAME: {
1967  // Compute the displacement of the camera since the previous call
1968  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1969 
1970  // Compute the ThetaU representation for the rotation
1971  vpRotationMatrix cRc;
1972  cMc.extract(cRc);
1973  vpThetaUVector thetaU;
1974  thetaU.buildFrom(cRc);
1975 
1976  for (unsigned int i=0; i < 3; i++) {
1977  // Compute the translation displacement in the reference frame
1978  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1979  // Update the rotation displacement in the camera frame
1980  velocity[i+3] = thetaU[i];
1981  }
1982 
1983  // Compute the velocity
1984  velocity /= (time_cur - time_prev_getvel);
1985  break ;
1986  }
1987  }
1988  }
1989  else {
1990  first_time_getvel = false;
1991  }
1992 
1993  // Memorize the camera pose for the next call
1994  fMc_prev_getvel = fMc_cur;
1995 
1996  // Memorize the joint position for the next call
1997  q_prev_getvel = q_cur;
1998 
1999  // Memorize the time associated to the joint position for the next call
2000  time_prev_getvel = time_cur;
2001 
2002 
2003  CatchPrint();
2004  if (TryStt < 0) {
2005  vpERROR_TRACE ("Cannot get velocity.");
2007  "Cannot get velocity.");
2008  }
2009 }
2010 
2020  vpColVector & velocity)
2021 {
2022  double timestamp;
2023  getVelocity(frame, velocity, timestamp);
2024 }
2025 
2077 {
2078  vpColVector velocity;
2079  getVelocity (frame, velocity, timestamp);
2080 
2081  return velocity;
2082 }
2083 
2093 {
2094  vpColVector velocity;
2095  double timestamp;
2096  getVelocity (frame, velocity, timestamp);
2097 
2098  return velocity;
2099 }
2100 
2166 bool vpRobotViper850::readPosFile(const std::string &filename, vpColVector &q)
2167 {
2168  std::ifstream fd(filename.c_str(), std::ios::in);
2169 
2170  if(! fd.is_open()) {
2171  return false;
2172  }
2173 
2174  std::string line;
2175  std::string key("R:");
2176  std::string id("#Viper850 - Position");
2177  bool pos_found = false;
2178  int lineNum = 0;
2179 
2180  q.resize(njoint);
2181 
2182  while(std::getline(fd, line)) {
2183  lineNum ++;
2184  if (lineNum == 1) {
2185  if(! (line.compare(0, id.size(), id) == 0)) { // check if Viper850 position file
2186  std::cout << "Error: this position file " << filename << " is not for Viper850 robot" << std::endl;
2187  return false;
2188  }
2189  }
2190  if((line.compare(0, 1, "#") == 0)) { // skip comment
2191  continue;
2192  }
2193  if((line.compare(0, key.size(), key) == 0)) { // decode position
2194  // check if there are at least njoint values in the line
2195  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2196  if (chain.size() < njoint+1) // try to split with tab separator
2197  chain = vpIoTools::splitChain(line, std::string("\t"));
2198  if(chain.size() < njoint+1)
2199  continue;
2200 
2201  std::istringstream ss(line);
2202  std::string key_;
2203  ss >> key_;
2204  for (unsigned int i=0; i< njoint; i++)
2205  ss >> q[i];
2206  pos_found = true;
2207  break;
2208  }
2209  }
2210 
2211  // converts rotations from degrees into radians
2212  q.deg2rad();
2213 
2214  fd.close();
2215 
2216  if (!pos_found) {
2217  std::cout << "Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2218  return false;
2219  }
2220 
2221  return true;
2222 }
2223 
2247 bool
2248  vpRobotViper850::savePosFile(const std::string &filename, const vpColVector &q)
2249 {
2250 
2251  FILE * fd ;
2252  fd = fopen(filename.c_str(), "w") ;
2253  if (fd == NULL)
2254  return false;
2255 
2256  fprintf(fd, "\
2257 #Viper850 - Position - Version 1.00\n\
2258 #\n\
2259 # R: A B C D E F\n\
2260 # Joint position in degrees\n\
2261 #\n\
2262 #\n\n");
2263 
2264  // Save positions in mm and deg
2265  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2266  vpMath::deg(q[0]),
2267  vpMath::deg(q[1]),
2268  vpMath::deg(q[2]),
2269  vpMath::deg(q[3]),
2270  vpMath::deg(q[4]),
2271  vpMath::deg(q[5]));
2272 
2273  fclose(fd) ;
2274  return (true);
2275 }
2276 
2287 void
2288  vpRobotViper850::move(const std::string &filename)
2289 {
2290  vpColVector q;
2291 
2292  try {
2293  this->readPosFile(filename, q) ;
2295  this->setPositioningVelocity(10);
2297  }
2298  catch(...) {
2299  throw;
2300  }
2301 }
2302 
2316 void
2317  vpRobotViper850::getCameraDisplacement(vpColVector &displacement)
2318 {
2319  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2320 }
2332 void
2333  vpRobotViper850::getArticularDisplacement(vpColVector &displacement)
2334 {
2336 }
2337 
2358 void
2360  vpColVector &displacement)
2361 {
2362  displacement.resize (6);
2363  displacement = 0;
2364 
2365  double q[6];
2366  vpColVector q_cur(6);
2367  double timestamp;
2368 
2369  InitTry;
2370 
2371  // Get the current joint position
2372  Try( PrimitiveACQ_POS_Viper850(q, &timestamp) );
2373  for (unsigned int i=0; i < njoint; i ++) {
2374  q_cur[i] = q[i];
2375  }
2376 
2377  if ( ! first_time_getdis ) {
2378  switch (frame) {
2379  case vpRobot::CAMERA_FRAME: {
2380  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2381  return;
2382  }
2383 
2384  case vpRobot::ARTICULAR_FRAME: {
2385  displacement = q_cur - q_prev_getdis;
2386  break ;
2387  }
2388 
2389  case vpRobot::REFERENCE_FRAME: {
2390  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2391  return;
2392  }
2393 
2394  case vpRobot::MIXT_FRAME: {
2395  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2396  return;
2397  }
2398  }
2399  }
2400  else {
2401  first_time_getdis = false;
2402  }
2403 
2404  // Memorize the joint position for the next call
2405  q_prev_getdis = q_cur;
2406 
2407  CatchPrint();
2408  if (TryStt < 0) {
2409  vpERROR_TRACE ("Cannot get velocity.");
2411  "Cannot get velocity.");
2412  }
2413 }
2414 
2423 {
2424 #if defined(USE_ATI_DAQ)
2425 # if defined(VISP_HAVE_COMEDI)
2426  ati.bias();
2427 # else
2428  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo apt-get install libcomedi-dev"));
2429 # endif
2430 #else // Use serial link
2431  InitTry;
2432 
2433  Try( PrimitiveTFS_BIAS_Viper850() );
2434 
2435  // Wait 500 ms to be sure the next measures take into account the bias
2436  vpTime::wait(500);
2437 
2438  CatchPrint();
2439  if (TryStt < 0) {
2440  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2442  "Cannot bias the force/torque sensor.");
2443  }
2444 #endif
2445 }
2446 
2455 {
2456 #if defined(USE_ATI_DAQ)
2457 # if defined(VISP_HAVE_COMEDI)
2458  ati.unbias();
2459 # else
2460  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo apt-get install libcomedi-dev"));
2461 # endif
2462 #else // Use serial link
2463  // Not implemented
2464 #endif
2465 }
2466 
2507 {
2508 #if defined(USE_ATI_DAQ)
2509 # if defined(VISP_HAVE_COMEDI)
2510  H = ati.getForceTorque();
2511 # else
2512  (void)H;
2513  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo apt-get install libcomedi-dev"));
2514 # endif
2515 #else // Use serial link
2516  InitTry;
2517 
2518  H.resize (6);
2519 
2520  Try( PrimitiveTFS_ACQ_Viper850(H.data) );
2521 
2522  CatchPrint();
2523  if (TryStt < 0) {
2524  vpERROR_TRACE ("Cannot get the force/torque measures.");
2526  "Cannot get force/torque measures.");
2527  }
2528 #endif
2529 }
2530 
2569 {
2570 #if defined(USE_ATI_DAQ)
2571 # if defined(VISP_HAVE_COMEDI)
2572  vpColVector H = ati.getForceTorque();
2573  return H;
2574 # else
2575  throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo apt-get install libcomedi-dev"));
2576 # endif
2577 #else // Use serial link
2578  InitTry;
2579 
2580  vpColVector H(6);
2581 
2582  Try( PrimitiveTFS_ACQ_Viper850(H.data) );
2583  return H;
2584 
2585  CatchPrint();
2586  if (TryStt < 0) {
2587  vpERROR_TRACE ("Cannot get the force/torque measures.");
2589  "Cannot get force/torque measures.");
2590  }
2591  return H; // Here to avoid a warning, but should never be called
2592 #endif
2593 }
2594 
2602 {
2603  InitTry;
2604  Try( PrimitivePneumaticGripper_Viper850(1) );
2605  std::cout << "Open the pneumatic gripper..." << std::endl;
2606  CatchPrint();
2607  if (TryStt < 0) {
2609  "Cannot open the gripper.");
2610  }
2611 }
2612 
2621 {
2622  InitTry;
2623  Try( PrimitivePneumaticGripper_Viper850(0) );
2624  std::cout << "Close the pneumatic gripper..." << std::endl;
2625  CatchPrint();
2626  if (TryStt < 0) {
2628  "Cannot close the gripper.");
2629  }
2630 }
2631 
2638 {
2639  InitTry;
2640  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0) );
2641  std::cout << "Enable joint limits on axis 6..." << std::endl;
2642  CatchPrint();
2643  if (TryStt < 0) {
2644  vpERROR_TRACE ("Cannot enable joint limits on axis 6");
2646  "Cannot enable joint limits on axis 6.");
2647  }
2648 }
2649 
2660 {
2661  InitTry;
2662  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1) );
2663  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2664  CatchPrint();
2665  if (TryStt < 0) {
2666  vpERROR_TRACE ("Cannot disable joint limits on axis 6");
2668  "Cannot disable joint limits on axis 6.");
2669  }
2670 }
2671 
2679 void
2681 {
2684 
2685  return;
2686 }
2687 
2707 void
2709 {
2710  maxRotationVelocity_joint6 = w6_max;
2711  return;
2712 }
2713 
2720 double
2722 {
2723  return maxRotationVelocity_joint6;
2724 }
2725 
2726 #elif !defined(VISP_BUILD_SHARED_LIBS)
2727 // Work arround to avoid warning: libvisp_robot.a(vpRobotViper850.cpp.o) has no symbols
2728 void dummy_vpRobotViper850() {};
2729 #endif
2730 
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:97
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:1002
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:157
Error that can be emited by the vpRobot class and its derivates.
double getPositioningVelocity(void) const
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:137
void closeGripper() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
Definition: vpRobot.h:157
#define vpERROR_TRACE
Definition: vpDebug.h:391
vpColVector getForceTorque() const
void setPositioningVelocity(const double velocity)
double maxRotationVelocity
Definition: vpRobot.h:95
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
void enableJoint6Limits() const
Initialize the position controller.
Definition: vpRobot.h:69
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
error that can be emited by ViSP classes.
Definition: vpException.h:73
Class that defines a generic virtual robot.
Definition: vpRobot.h:58
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:84
vpControlFrameType
Definition: vpRobot.h:76
vpRxyzVector erc
Definition: vpViper.h:157
void move(const std::string &filename)
void get_eJe(vpMatrix &eJe)
void disableJoint6Limits() const
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
void deg2rad()
Definition: vpColVector.h:127
Implementation of a rotation matrix and operations on such kind of matrices.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
static bool checkFilename(const char *filename)
Definition: vpIoTools.cpp:508
Initialize the velocity controller.
Definition: vpRobot.h:68
vpRobotStateType
Definition: vpRobot.h:64
bool verbose_
Definition: vpRobot.h:113
vpTranslationVector etc
Definition: vpViper.h:156
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1279
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRowVector t() const
vpColVector joint_max
Definition: vpViper.h:169
VISP_EXPORT void sleepMs(double t)
Definition: vpTime.cpp:266
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
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:616
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1596
vpColVector getForceTorque() const
bool getPowerState() const
Implementation of a velocity twist matrix and operations on such kind of matrices.
void get_fJe(vpMatrix &fJe)
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:578
static double rad(double deg)
Definition: vpMath.h:104
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1194
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:262
void get_cVe(vpVelocityTwistMatrix &cVe) const
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:948
void setMaxRotationVelocityJoint6(double w6_max)
static double deg(double rad)
Definition: vpMath.h:97
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
Manual control mode activated when the dead man switch is in use.
static const double defaultPositioningVelocity
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:141
double getMaxRotationVelocityJoint6() const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
Emergency stop activated.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRzyzVector.h:151
virtual ~vpRobotViper850(void)
void init(void)
Definition: vpViper850.cpp:134
void setCalibrationFile(const std::string &calibfile, unsigned short index=1)
Automatic control mode (default).
double getTime() const
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void rad2deg()
Definition: vpColVector.h:210
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:151
void get_cMe(vpHomogeneousMatrix &cMe) const
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:225
vpColVector joint_min
Definition: vpViper.h:170