Visual Servoing Platform  version 3.1.0
vpRobotViper650.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 S650 robot.
33  *
34  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
39 #include <visp3/core/vpConfig.h>
40 
41 #ifdef VISP_HAVE_VIPER650
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/vpRobotViper650.h>
56 
57 /* ---------------------------------------------------------------------- */
58 /* --- STATIC ----------------------------------------------------------- */
59 /* ---------------------------------------------------------------------- */
60 
61 bool vpRobotViper650::robotAlreadyCreated = false;
62 
71 
72 /* ---------------------------------------------------------------------- */
73 /* --- EMERGENCY STOP --------------------------------------------------- */
74 /* ---------------------------------------------------------------------- */
75 
83 void emergencyStopViper650(int signo)
84 {
85  std::cout << "Stop the Viper650 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_Viper650();
107  PrimitiveSTOP_Viper650();
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 
178 vpRobotViper650::vpRobotViper650(bool verbose) : vpViper650(), vpRobot()
179 {
180 
181  /*
182  #define SIGHUP 1 // hangup
183  #define SIGINT 2 // interrupt (rubout)
184  #define SIGQUIT 3 // quit (ASCII FS)
185  #define SIGILL 4 // illegal instruction (not reset when caught)
186  #define SIGTRAP 5 // trace trap (not reset when caught)
187  #define SIGIOT 6 // IOT instruction
188  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
189  #define SIGEMT 7 // EMT instruction
190  #define SIGFPE 8 // floating point exception
191  #define SIGKILL 9 // kill (cannot be caught or ignored)
192  #define SIGBUS 10 // bus error
193  #define SIGSEGV 11 // segmentation violation
194  #define SIGSYS 12 // bad argument to system call
195  #define SIGPIPE 13 // write on a pipe with no one to read it
196  #define SIGALRM 14 // alarm clock
197  #define SIGTERM 15 // software termination signal from kill
198  */
199 
200  signal(SIGINT, emergencyStopViper650);
201  signal(SIGBUS, emergencyStopViper650);
202  signal(SIGSEGV, emergencyStopViper650);
203  signal(SIGKILL, emergencyStopViper650);
204  signal(SIGQUIT, emergencyStopViper650);
205 
206  setVerbose(verbose);
207  if (verbose_)
208  std::cout << "Open communication with MotionBlox.\n";
209  try {
210  this->init();
212  } catch (...) {
213  // vpERROR_TRACE("Error caught") ;
214  throw;
215  }
216  positioningVelocity = defaultPositioningVelocity;
217 
218  maxRotationVelocity_joint6 = maxRotationVelocity;
219 
220  vpRobotViper650::robotAlreadyCreated = true;
221 
222  return;
223 }
224 
225 /* ------------------------------------------------------------------------ */
226 /* --- INITIALISATION ----------------------------------------------------- */
227 /* ------------------------------------------------------------------------ */
228 
252 {
253  InitTry;
254 
255  // Initialise private variables used to compute the measured velocities
256  q_prev_getvel.resize(6);
257  q_prev_getvel = 0;
258  time_prev_getvel = 0;
259  first_time_getvel = true;
260 
261  // Initialise private variables used to compute the measured displacement
262  q_prev_getdis.resize(6);
263  q_prev_getdis = 0;
264  first_time_getdis = true;
265 
266  // Initialize the firewire connection
267  Try(InitializeConnection(verbose_));
268 
269  // Connect to the servoboard using the servo board GUID
270  Try(InitializeNode_Viper650());
271 
272  Try(PrimitiveRESET_Viper650());
273 
274  // Enable the joint limits on axis 6
275  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
276 
277  // Update the eMc matrix in the low level controller
279 
280  // Look if the power is on or off
281  UInt32 HIPowerStatus;
282  UInt32 EStopStatus;
283  Try(PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus));
284  CAL_Wait(0.1);
285 
286  // Print the robot status
287  if (verbose_) {
288  std::cout << "Robot status: ";
289  switch (EStopStatus) {
290  case ESTOP_AUTO:
291  controlMode = AUTO;
292  if (HIPowerStatus == 0)
293  std::cout << "Power is OFF" << std::endl;
294  else
295  std::cout << "Power is ON" << std::endl;
296  break;
297 
298  case ESTOP_MANUAL:
299  controlMode = MANUAL;
300  if (HIPowerStatus == 0)
301  std::cout << "Power is OFF" << std::endl;
302  else
303  std::cout << "Power is ON" << std::endl;
304  break;
305  case ESTOP_ACTIVATED:
306  controlMode = ESTOP;
307  std::cout << "Emergency stop is activated" << std::endl;
308  break;
309  default:
310  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
311  std::cout << "You have to call Adept for maintenance..." << std::endl;
312  // Free allocated resources
313  }
314  std::cout << std::endl;
315  }
316  // get real joint min/max from the MotionBlox
317  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
318  // Convert units from degrees to radians
319  joint_min.deg2rad();
320  joint_max.deg2rad();
321 
322  // for (unsigned int i=0; i < njoint; i++) {
323  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
324  // joint_max[i]);
325  // }
326 
327  // If an error occur in the low level controller, goto here
328  // CatchPrint();
329  Catch();
330 
331  // Test if an error occurs
332  if (TryStt == -20001)
333  printf("No connection detected. Check if the robot is powered on \n"
334  "and if the firewire link exist between the MotionBlox and this "
335  "computer.\n");
336  else if (TryStt == -675)
337  printf(" Timeout enabling power...\n");
338 
339  if (TryStt < 0) {
340  // Power off the robot
341  PrimitivePOWEROFF_Viper650();
342  // Free allocated resources
343  ShutDownConnection();
344 
345  std::cout << "Cannot open connection with the motionblox..." << std::endl;
346  throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with the motionblox");
347  }
348  return;
349 }
350 
409 {
410  // Read the robot constants from files
411  // - joint [min,max], coupl_56, long_56
412  // - camera extrinsic parameters relative to eMc
413  vpViper650::init(tool, projModel);
414 
415  InitTry;
416 
417  // Get real joint min/max from the MotionBlox
418  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
419  // Convert units from degrees to radians
420  joint_min.deg2rad();
421  joint_max.deg2rad();
422 
423  // for (unsigned int i=0; i < njoint; i++) {
424  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
425  // joint_max[i]);
426  // }
427 
428  // Set the camera constant (eMc pose) in the MotionBlox
429  double eMc_pose[6];
430  for (unsigned int i = 0; i < 3; i++) {
431  eMc_pose[i] = etc[i]; // translation in meters
432  eMc_pose[i + 3] = erc[i]; // rotation in rad
433  }
434  // Update the eMc pose in the low level controller
435  Try(PrimitiveCONST_Viper650(eMc_pose));
436 
437  CatchPrint();
438  return;
439 }
440 
491 void vpRobotViper650::init(vpViper650::vpToolType tool, const std::string &filename)
492 {
493  vpViper650::init(tool, filename);
494 
495  InitTry;
496 
497  // Get real joint min/max from the MotionBlox
498  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
499  // Convert units from degrees to radians
500  joint_min.deg2rad();
501  joint_max.deg2rad();
502 
503  // for (unsigned int i=0; i < njoint; i++) {
504  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
505  // joint_max[i]);
506  // }
507 
508  // Set the camera constant (eMc pose) in the MotionBlox
509  double eMc_pose[6];
510  for (unsigned int i = 0; i < 3; i++) {
511  eMc_pose[i] = etc[i]; // translation in meters
512  eMc_pose[i + 3] = erc[i]; // rotation in rad
513  }
514  // Update the eMc pose in the low level controller
515  Try(PrimitiveCONST_Viper650(eMc_pose));
516 
517  CatchPrint();
518  return;
519 }
520 
558 {
559  vpViper650::init(tool, eMc_);
560 
561  InitTry;
562 
563  // Get real joint min/max from the MotionBlox
564  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
565  // Convert units from degrees to radians
566  joint_min.deg2rad();
567  joint_max.deg2rad();
568 
569  // for (unsigned int i=0; i < njoint; i++) {
570  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
571  // joint_max[i]);
572  // }
573 
574  // Set the camera constant (eMc pose) in the MotionBlox
575  double eMc_pose[6];
576  for (unsigned int i = 0; i < 3; i++) {
577  eMc_pose[i] = etc[i]; // translation in meters
578  eMc_pose[i + 3] = erc[i]; // rotation in rad
579  }
580  // Update the eMc pose in the low level controller
581  Try(PrimitiveCONST_Viper650(eMc_pose));
582 
583  CatchPrint();
584  return;
585 }
586 
599 {
600  this->vpViper650::set_eMc(eMc_);
601 
602  InitTry;
603 
604  // Set the camera constant (eMc pose) in the MotionBlox
605  double eMc_pose[6];
606  for (unsigned int i = 0; i < 3; i++) {
607  eMc_pose[i] = etc[i]; // translation in meters
608  eMc_pose[i + 3] = erc[i]; // rotation in rad
609  }
610  // Update the eMc pose in the low level controller
611  Try(PrimitiveCONST_Viper650(eMc_pose));
612 
613  CatchPrint();
614 
615  return;
616 }
617 
631 {
632  this->vpViper650::set_eMc(etc_, erc_);
633 
634  InitTry;
635 
636  // Set the camera constant (eMc pose) in the MotionBlox
637  double eMc_pose[6];
638  for (unsigned int i = 0; i < 3; i++) {
639  eMc_pose[i] = etc[i]; // translation in meters
640  eMc_pose[i + 3] = erc[i]; // rotation in rad
641  }
642  // Update the eMc pose in the low level controller
643  Try(PrimitiveCONST_Viper650(eMc_pose));
644 
645  CatchPrint();
646 
647  return;
648 }
649 
650 /* ------------------------------------------------------------------------ */
651 /* --- DESTRUCTOR --------------------------------------------------------- */
652 /* ------------------------------------------------------------------------ */
653 
661 {
662  InitTry;
663 
665 
666  // Look if the power is on or off
667  UInt32 HIPowerStatus;
668  Try(PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus));
669  CAL_Wait(0.1);
670 
671  // if (HIPowerStatus == 1) {
672  // fprintf(stdout, "Power OFF the robot\n");
673  // fflush(stdout);
674 
675  // Try( PrimitivePOWEROFF_Viper650() );
676  // }
677 
678  // Free allocated resources
679  ShutDownConnection();
680 
681  vpRobotViper650::robotAlreadyCreated = false;
682 
683  CatchPrint();
684  return;
685 }
686 
694 {
695  InitTry;
696 
697  switch (newState) {
698  case vpRobot::STATE_STOP: {
699  // Start primitive STOP only if the current state is Velocity
701  Try(PrimitiveSTOP_Viper650());
702  vpTime::sleepMs(100); // needed to ensure velocity task ends up on low level
703  }
704  break;
705  }
708  std::cout << "Change the control mode from velocity to position control.\n";
709  Try(PrimitiveSTOP_Viper650());
710  } else {
711  // std::cout << "Change the control mode from stop to position
712  // control.\n";
713  }
714  this->powerOn();
715  break;
716  }
719  std::cout << "Change the control mode from stop to velocity control.\n";
720  }
721  this->powerOn();
722  break;
723  }
724  default:
725  break;
726  }
727 
728  CatchPrint();
729 
730  return vpRobot::setRobotState(newState);
731 }
732 
733 /* ------------------------------------------------------------------------ */
734 /* --- STOP --------------------------------------------------------------- */
735 /* ------------------------------------------------------------------------ */
736 
745 {
747  return;
748 
749  InitTry;
750  Try(PrimitiveSTOP_Viper650());
752 
753  CatchPrint();
754  if (TryStt < 0) {
755  vpERROR_TRACE("Cannot stop robot motion");
756  throw vpRobotException(vpRobotException::lowLevelError, "Cannot stop robot motion.");
757  }
758 }
759 
770 {
771  InitTry;
772 
773  // Look if the power is on or off
774  UInt32 HIPowerStatus;
775  UInt32 EStopStatus;
776  bool firsttime = true;
777  unsigned int nitermax = 10;
778 
779  for (unsigned int i = 0; i < nitermax; i++) {
780  Try(PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL, &HIPowerStatus));
781  if (EStopStatus == ESTOP_AUTO) {
782  controlMode = AUTO;
783  break; // exit for loop
784  } else if (EStopStatus == ESTOP_MANUAL) {
785  controlMode = MANUAL;
786  break; // exit for loop
787  } else if (EStopStatus == ESTOP_ACTIVATED) {
788  controlMode = ESTOP;
789  if (firsttime) {
790  std::cout << "Emergency stop is activated! \n"
791  << "Check the emergency stop button and push the yellow "
792  "button before continuing."
793  << std::endl;
794  firsttime = false;
795  }
796  fprintf(stdout, "Remaining time %us \r", nitermax - i);
797  fflush(stdout);
798  CAL_Wait(1);
799  } else {
800  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
801  std::cout << "You have to call Adept for maintenance..." << std::endl;
802  // Free allocated resources
803  ShutDownConnection();
804  exit(0);
805  }
806  }
807 
808  if (EStopStatus == ESTOP_ACTIVATED)
809  std::cout << std::endl;
810 
811  if (EStopStatus == ESTOP_ACTIVATED) {
812  std::cout << "Sorry, cannot power on the robot." << std::endl;
813  throw vpRobotException(vpRobotException::lowLevelError, "Cannot power on the robot.");
814  }
815 
816  if (HIPowerStatus == 0) {
817  fprintf(stdout, "Power ON the Viper650 robot\n");
818  fflush(stdout);
819 
820  Try(PrimitivePOWERON_Viper650());
821  }
822 
823  CatchPrint();
824  if (TryStt < 0) {
825  vpERROR_TRACE("Cannot power on the robot");
826  throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
827  }
828 }
829 
840 {
841  InitTry;
842 
843  // Look if the power is on or off
844  UInt32 HIPowerStatus;
845  Try(PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus));
846  CAL_Wait(0.1);
847 
848  if (HIPowerStatus == 1) {
849  fprintf(stdout, "Power OFF the Viper650 robot\n");
850  fflush(stdout);
851 
852  Try(PrimitivePOWEROFF_Viper650());
853  }
854 
855  CatchPrint();
856  if (TryStt < 0) {
857  vpERROR_TRACE("Cannot power off the robot");
858  throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
859  }
860 }
861 
874 {
875  InitTry;
876  bool status = false;
877  // Look if the power is on or off
878  UInt32 HIPowerStatus;
879  Try(PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL, &HIPowerStatus));
880  CAL_Wait(0.1);
881 
882  if (HIPowerStatus == 1) {
883  status = true;
884  }
885 
886  CatchPrint();
887  if (TryStt < 0) {
888  vpERROR_TRACE("Cannot get the power status");
889  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get the power status.");
890  }
891  return status;
892 }
893 
904 {
906  vpViper650::get_cMe(cMe);
907 
908  cVe.buildFrom(cMe);
909 }
910 
923 
936 {
937 
938  double position[6];
939  double timestamp;
940 
941  InitTry;
942  Try(PrimitiveACQ_POS_J_Viper650(position, &timestamp));
943  CatchPrint();
944 
945  vpColVector q(6);
946  for (unsigned int i = 0; i < njoint; i++)
947  q[i] = vpMath::rad(position[i]);
948 
949  try {
950  vpViper650::get_eJe(q, eJe);
951  } catch (...) {
952  vpERROR_TRACE("catch exception ");
953  throw;
954  }
955 }
969 {
970 
971  double position[6];
972  double timestamp;
973 
974  InitTry;
975  Try(PrimitiveACQ_POS_Viper650(position, &timestamp));
976  CatchPrint();
977 
978  vpColVector q(6);
979  for (unsigned int i = 0; i < njoint; i++)
980  q[i] = position[i];
981 
982  try {
983  vpViper650::get_fJe(q, fJe);
984  } catch (...) {
985  vpERROR_TRACE("Error caught");
986  throw;
987  }
988 }
989 
1027 void vpRobotViper650::setPositioningVelocity(const double velocity) { positioningVelocity = velocity; }
1028 
1034 double vpRobotViper650::getPositioningVelocity(void) const { return positioningVelocity; }
1035 
1115 {
1116 
1118  vpERROR_TRACE("Robot was not in position-based control\n"
1119  "Modification of the robot state");
1121  }
1122 
1123  vpColVector destination(njoint);
1124  int error = 0;
1125  double timestamp;
1126 
1127  InitTry;
1128  switch (frame) {
1129  case vpRobot::CAMERA_FRAME: {
1130  vpColVector q(njoint);
1131  Try(PrimitiveACQ_POS_Viper650(q.data, &timestamp));
1132 
1133  // Convert degrees into rad
1134  q.deg2rad();
1135 
1136  // Get fMc from the inverse kinematics
1137  vpHomogeneousMatrix fMc;
1138  vpViper650::get_fMc(q, fMc);
1139 
1140  // Set cMc from the input position
1141  vpTranslationVector txyz;
1142  vpRxyzVector rxyz;
1143  for (unsigned int i = 0; i < 3; i++) {
1144  txyz[i] = position[i];
1145  rxyz[i] = position[i + 3];
1146  }
1147 
1148  // Compute cMc2
1149  vpRotationMatrix cRc2(rxyz);
1150  vpHomogeneousMatrix cMc2(txyz, cRc2);
1151 
1152  // Compute the new position to reach: fMc*cMc2
1153  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1154 
1155  // Compute the corresponding joint position from the inverse kinematics
1156  unsigned int solution = this->getInverseKinematics(fMc2, q);
1157  if (solution) { // Position is reachable
1158  destination = q;
1159  // convert rad to deg requested for the low level controller
1160  destination.rad2deg();
1161  Try(PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity));
1162  Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1163  } else {
1164  // Cartesian position is out of range
1165  error = -1;
1166  }
1167 
1168  break;
1169  }
1170  case vpRobot::ARTICULAR_FRAME: {
1171  destination = position;
1172  // convert rad to deg requested for the low level controller
1173  destination.rad2deg();
1174 
1175  // std::cout << "Joint destination (deg): " << destination.t() <<
1176  // std::endl;
1177  Try(PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity));
1178  Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1179  break;
1180  }
1181  case vpRobot::REFERENCE_FRAME: {
1182  // Convert angles from Rxyz representation to Rzyz representation
1183  vpRxyzVector rxyz(position[3], position[4], position[5]);
1184  vpRotationMatrix R(rxyz);
1185  vpRzyzVector rzyz(R);
1186 
1187  for (unsigned int i = 0; i < 3; i++) {
1188  destination[i] = position[i];
1189  destination[i + 3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1190  }
1191  int configuration = 0; // keep the actual configuration
1192 
1193  // std::cout << "Base frame destination Rzyz (deg): " << destination.t()
1194  // << std::endl;
1195  Try(PrimitiveMOVE_C_Viper650(destination.data, configuration, positioningVelocity));
1196  Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1197 
1198  break;
1199  }
1200  case vpRobot::MIXT_FRAME: {
1201  vpERROR_TRACE("Positionning error. Mixt frame not implemented");
1202  throw vpRobotException(vpRobotException::lowLevelError, "Positionning error: "
1203  "Mixt frame not implemented.");
1204  }
1205  }
1206 
1207  CatchPrint();
1208  if (TryStt == InvalidPosition || TryStt == -1023)
1209  std::cout << " : Position out of range.\n";
1210 
1211  else if (TryStt == -3019) {
1212  if (frame == vpRobot::ARTICULAR_FRAME)
1213  std::cout << " : Joint position out of range.\n";
1214  else
1215  std::cout << " : Cartesian position leads to a joint position out of "
1216  "range.\n";
1217  } else if (TryStt < 0)
1218  std::cout << " : Unknown error (see Fabien).\n";
1219  else if (error == -1)
1220  std::cout << "Position out of range.\n";
1221 
1222  if (TryStt < 0 || error < 0) {
1223  vpERROR_TRACE("Positionning error.");
1224  throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1225  }
1226 
1227  return;
1228 }
1229 
1295 void vpRobotViper650::setPosition(const vpRobot::vpControlFrameType frame, const double pos1, const double pos2,
1296  const double pos3, const double pos4, const double pos5, const double pos6)
1297 {
1298  try {
1299  vpColVector position(6);
1300  position[0] = pos1;
1301  position[1] = pos2;
1302  position[2] = pos3;
1303  position[3] = pos4;
1304  position[4] = pos5;
1305  position[5] = pos6;
1306 
1307  setPosition(frame, position);
1308  } catch (...) {
1309  vpERROR_TRACE("Error caught");
1310  throw;
1311  }
1312 }
1313 
1353 void vpRobotViper650::setPosition(const std::string &filename)
1354 {
1355  vpColVector q;
1356  bool ret;
1357 
1358  ret = this->readPosFile(filename, q);
1359 
1360  if (ret == false) {
1361  vpERROR_TRACE("Bad position in \"%s\"", filename.c_str());
1362  throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1363  }
1366 }
1367 
1436 void vpRobotViper650::getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp)
1437 {
1438 
1439  InitTry;
1440 
1441  position.resize(6);
1442 
1443  switch (frame) {
1444  case vpRobot::CAMERA_FRAME: {
1445  position = 0;
1446  return;
1447  }
1448  case vpRobot::ARTICULAR_FRAME: {
1449  Try(PrimitiveACQ_POS_J_Viper650(position.data, &timestamp));
1450  // vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1451  position.deg2rad();
1452 
1453  return;
1454  }
1455  case vpRobot::REFERENCE_FRAME: {
1456  Try(PrimitiveACQ_POS_C_Viper650(position.data, &timestamp));
1457  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1458  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1459  // Convert Euler Rzyz angles from deg to rad
1460  for (unsigned int i = 3; i < 6; i++)
1461  position[i] = vpMath::rad(position[i]);
1462  // Convert Rzyz angles into Rxyz representation
1463  vpRzyzVector rzyz(position[3], position[4], position[5]);
1464  vpRotationMatrix R(rzyz);
1465  vpRxyzVector rxyz(R);
1466 
1467  // Update the position using Rxyz representation
1468  for (unsigned int i = 0; i < 3; i++)
1469  position[i + 3] = rxyz[i];
1470  // vpCTRACE << "Cartesian position Rxyz (deg)"
1471  // << position[0] << " " << position[1] << " " << position[2] << " "
1472  // << vpMath::deg(position[3]) << " "
1473  // << vpMath::deg(position[4]) << " "
1474  // << vpMath::deg(position[5]) << std::endl;
1475 
1476  break;
1477  }
1478  case vpRobot::MIXT_FRAME: {
1479  vpERROR_TRACE("Cannot get position in mixt frame: not implemented");
1480  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
1481  "not implemented");
1482  }
1483  }
1484 
1485  CatchPrint();
1486  if (TryStt < 0) {
1487  vpERROR_TRACE("Cannot get position.");
1488  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position.");
1489  }
1490 
1491  return;
1492 }
1493 
1505 {
1506  double timestamp;
1507  getPosition(frame, position, timestamp);
1508 }
1509 
1523 void vpRobotViper650::getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
1524 {
1525  vpColVector posRxyz;
1526  // recupere position en Rxyz
1527  this->getPosition(frame, posRxyz, timestamp);
1528  vpRxyzVector RxyzVect;
1529  for (unsigned int j = 0; j < 3; j++)
1530  RxyzVect[j] = posRxyz[j + 3];
1531  // recupere le vecteur thetaU correspondant
1532  vpThetaUVector RtuVect(RxyzVect);
1533 
1534  // remplit le vpPoseVector avec translation et rotation ThetaU
1535  for (unsigned int j = 0; j < 3; j++) {
1536  position[j] = posRxyz[j];
1537  position[j + 3] = RtuVect[j];
1538  }
1539 }
1540 
1552 {
1553  double timestamp;
1554  getPosition(frame, position, timestamp);
1555 }
1556 
1562 {
1563  double timestamp;
1564  PrimitiveACQ_TIME_Viper650(&timestamp);
1565  return timestamp;
1566 }
1567 
1647 {
1649  vpERROR_TRACE("Cannot send a velocity to the robot "
1650  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1652  "Cannot send a velocity to the robot "
1653  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1654  }
1655 
1656  vpColVector vel_sat(6);
1657 
1658  // Velocity saturation
1659  switch (frame) {
1660  // saturation in cartesian space
1661  case vpRobot::CAMERA_FRAME:
1663  case vpRobot::MIXT_FRAME: {
1664  vpColVector vel_max(6);
1665 
1666  for (unsigned int i = 0; i < 3; i++)
1667  vel_max[i] = getMaxTranslationVelocity();
1668  for (unsigned int i = 3; i < 6; i++)
1669  vel_max[i] = getMaxRotationVelocity();
1670 
1671  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1672 
1673  break;
1674  }
1675  // saturation in joint space
1676  case vpRobot::ARTICULAR_FRAME: {
1677  vpColVector vel_max(6);
1678 
1679  // if (getMaxRotationVelocity() == getMaxRotationVelocityJoint6()) {
1680  if (std::fabs(getMaxRotationVelocity() - getMaxRotationVelocityJoint6()) < std::numeric_limits<double>::epsilon()) {
1681  for (unsigned int i = 0; i < 6; i++)
1682  vel_max[i] = getMaxRotationVelocity();
1683  } else {
1684  for (unsigned int i = 0; i < 5; i++)
1685  vel_max[i] = getMaxRotationVelocity();
1686  vel_max[5] = getMaxRotationVelocityJoint6();
1687  }
1688 
1689  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1690  }
1691  }
1692 
1693  InitTry;
1694 
1695  switch (frame) {
1696  case vpRobot::CAMERA_FRAME: {
1697  // Send velocities in m/s and rad/s
1698  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1699  Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPCAM_VIPER650));
1700  break;
1701  }
1702  case vpRobot::ARTICULAR_FRAME: {
1703  // Convert all the velocities from rad/s into deg/s
1704  vel_sat.rad2deg();
1705  // std::cout << "Vitesse appliquee: " << vel_sat.t();
1706  // Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER650) );
1707  Try(PrimitiveMOVESPEED_Viper650(vel_sat.data));
1708  break;
1709  }
1710  case vpRobot::REFERENCE_FRAME: {
1711  // Send velocities in m/s and rad/s
1712  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1713  Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPFIX_VIPER650));
1714  break;
1715  }
1716  case vpRobot::MIXT_FRAME: {
1717  // Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPMIX_VIPER650) );
1718  break;
1719  }
1720  default: {
1721  vpERROR_TRACE("Error in spec of vpRobot. "
1722  "Case not taken in account.");
1723  return;
1724  }
1725  }
1726 
1727  Catch();
1728  if (TryStt < 0) {
1729  if (TryStt == VelStopOnJoint) {
1730  UInt32 axisInJoint[njoint];
1731  PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1732  for (unsigned int i = 0; i < njoint; i++) {
1733  if (axisInJoint[i])
1734  std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl;
1735  }
1736  } else {
1737  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1738  if (TryString != NULL) {
1739  // The statement is in TryString, but we need to check the validity
1740  printf(" Error sentence %s\n", TryString); // Print the TryString
1741  } else {
1742  printf("\n");
1743  }
1744  }
1745  }
1746 
1747  return;
1748 }
1749 
1750 /* ------------------------------------------------------------------------ */
1751 /* --- GET ---------------------------------------------------------------- */
1752 /* ------------------------------------------------------------------------ */
1753 
1811 void vpRobotViper650::getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp)
1812 {
1813  velocity.resize(6);
1814  velocity = 0;
1815 
1816  vpColVector q_cur(6);
1817  vpHomogeneousMatrix fMc_cur;
1818  vpHomogeneousMatrix cMc; // camera displacement
1819  double time_cur;
1820 
1821  InitTry;
1822 
1823  // Get the current joint position
1824  Try(PrimitiveACQ_POS_J_Viper650(q_cur.data, &timestamp));
1825  time_cur = timestamp;
1826  q_cur.deg2rad();
1827 
1828  // Get the camera pose from the direct kinematics
1829  vpViper650::get_fMc(q_cur, fMc_cur);
1830 
1831  if (!first_time_getvel) {
1832 
1833  switch (frame) {
1834  case vpRobot::CAMERA_FRAME: {
1835  // Compute the displacement of the camera since the previous call
1836  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1837 
1838  // Compute the velocity of the camera from this displacement
1839  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1840 
1841  break;
1842  }
1843 
1844  case vpRobot::ARTICULAR_FRAME: {
1845  velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1846  break;
1847  }
1848 
1849  case vpRobot::REFERENCE_FRAME: {
1850  // Compute the displacement of the camera since the previous call
1851  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1852 
1853  // Compute the velocity of the camera from this displacement
1854  vpColVector v;
1855  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1856 
1857  // Express this velocity in the reference frame
1858  vpVelocityTwistMatrix fVc(fMc_cur);
1859  velocity = fVc * v;
1860 
1861  break;
1862  }
1863 
1864  case vpRobot::MIXT_FRAME: {
1865  // Compute the displacement of the camera since the previous call
1866  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1867 
1868  // Compute the ThetaU representation for the rotation
1869  vpRotationMatrix cRc;
1870  cMc.extract(cRc);
1871  vpThetaUVector thetaU;
1872  thetaU.buildFrom(cRc);
1873 
1874  for (unsigned int i = 0; i < 3; i++) {
1875  // Compute the translation displacement in the reference frame
1876  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1877  // Update the rotation displacement in the camera frame
1878  velocity[i + 3] = thetaU[i];
1879  }
1880 
1881  // Compute the velocity
1882  velocity /= (time_cur - time_prev_getvel);
1883  break;
1884  }
1885  }
1886  } else {
1887  first_time_getvel = false;
1888  }
1889 
1890  // Memorize the camera pose for the next call
1891  fMc_prev_getvel = fMc_cur;
1892 
1893  // Memorize the joint position for the next call
1894  q_prev_getvel = q_cur;
1895 
1896  // Memorize the time associated to the joint position for the next call
1897  time_prev_getvel = time_cur;
1898 
1899  CatchPrint();
1900  if (TryStt < 0) {
1901  vpERROR_TRACE("Cannot get velocity.");
1902  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
1903  }
1904 }
1905 
1915 {
1916  double timestamp;
1917  getVelocity(frame, velocity, timestamp);
1918 }
1919 
1971 {
1972  vpColVector velocity;
1973  getVelocity(frame, velocity, timestamp);
1974 
1975  return velocity;
1976 }
1977 
1987 {
1988  vpColVector velocity;
1989  double timestamp;
1990  getVelocity(frame, velocity, timestamp);
1991 
1992  return velocity;
1993 }
1994 
2061 bool vpRobotViper650::readPosFile(const std::string &filename, vpColVector &q)
2062 {
2063  std::ifstream fd(filename.c_str(), std::ios::in);
2064 
2065  if (!fd.is_open()) {
2066  return false;
2067  }
2068 
2069  std::string line;
2070  std::string key("R:");
2071  std::string id("#Viper650 - Position");
2072  bool pos_found = false;
2073  int lineNum = 0;
2074 
2075  q.resize(njoint);
2076 
2077  while (std::getline(fd, line)) {
2078  lineNum++;
2079  if (lineNum == 1) {
2080  if (!(line.compare(0, id.size(), id) == 0)) { // check if Viper650 position file
2081  std::cout << "Error: this position file " << filename << " is not for Viper650 robot" << std::endl;
2082  return false;
2083  }
2084  }
2085  if ((line.compare(0, 1, "#") == 0)) { // skip comment
2086  continue;
2087  }
2088  if ((line.compare(0, key.size(), key) == 0)) { // decode position
2089  // check if there are at least njoint values in the line
2090  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2091  if (chain.size() < njoint + 1) // try to split with tab separator
2092  chain = vpIoTools::splitChain(line, std::string("\t"));
2093  if (chain.size() < njoint + 1)
2094  continue;
2095 
2096  std::istringstream ss(line);
2097  std::string key_;
2098  ss >> key_;
2099  for (unsigned int i = 0; i < njoint; i++)
2100  ss >> q[i];
2101  pos_found = true;
2102  break;
2103  }
2104  }
2105 
2106  // converts rotations from degrees into radians
2107  q.deg2rad();
2108 
2109  fd.close();
2110 
2111  if (!pos_found) {
2112  std::cout << "Error: unable to find a position for Viper650 robot in " << filename << std::endl;
2113  return false;
2114  }
2115 
2116  return true;
2117 }
2118 
2142 bool vpRobotViper650::savePosFile(const std::string &filename, const vpColVector &q)
2143 {
2144 
2145  FILE *fd;
2146  fd = fopen(filename.c_str(), "w");
2147  if (fd == NULL)
2148  return false;
2149 
2150  fprintf(fd, "\
2151 #Viper650 - Position - Version 1.00\n\
2152 #\n\
2153 # R: A B C D E F\n\
2154 # Joint position in degrees\n\
2155 #\n\
2156 #\n\n");
2157 
2158  // Save positions in mm and deg
2159  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
2160  vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]));
2161 
2162  fclose(fd);
2163  return (true);
2164 }
2165 
2176 void vpRobotViper650::move(const std::string &filename)
2177 {
2178  vpColVector q;
2179 
2180  try {
2181  this->readPosFile(filename, q);
2183  this->setPositioningVelocity(10);
2185  } catch (...) {
2186  throw;
2187  }
2188 }
2189 
2209 {
2210  displacement.resize(6);
2211  displacement = 0;
2212 
2213  double q[6];
2214  vpColVector q_cur(6);
2215  double timestamp;
2216 
2217  InitTry;
2218 
2219  // Get the current joint position
2220  Try(PrimitiveACQ_POS_Viper650(q, &timestamp));
2221  for (unsigned int i = 0; i < njoint; i++) {
2222  q_cur[i] = q[i];
2223  }
2224 
2225  if (!first_time_getdis) {
2226  switch (frame) {
2227  case vpRobot::CAMERA_FRAME: {
2228  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2229  return;
2230  }
2231 
2232  case vpRobot::ARTICULAR_FRAME: {
2233  displacement = q_cur - q_prev_getdis;
2234  break;
2235  }
2236 
2237  case vpRobot::REFERENCE_FRAME: {
2238  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2239  return;
2240  }
2241 
2242  case vpRobot::MIXT_FRAME: {
2243  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2244  return;
2245  }
2246  }
2247  } else {
2248  first_time_getdis = false;
2249  }
2250 
2251  // Memorize the joint position for the next call
2252  q_prev_getdis = q_cur;
2253 
2254  CatchPrint();
2255  if (TryStt < 0) {
2256  vpERROR_TRACE("Cannot get velocity.");
2257  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
2258  }
2259 }
2260 
2275 {
2276  InitTry;
2277 
2278  Try(PrimitiveTFS_BIAS_Viper650());
2279 
2280  // Wait 500 ms to be sure the next measures take into account the bias
2281  vpTime::wait(500);
2282 
2283  CatchPrint();
2284  if (TryStt < 0) {
2285  vpERROR_TRACE("Cannot bias the force/torque sensor.");
2286  throw vpRobotException(vpRobotException::lowLevelError, "Cannot bias the force/torque sensor.");
2287  }
2288 }
2289 
2331 {
2332  InitTry;
2333 
2334  H.resize(6);
2335 
2336  Try(PrimitiveTFS_ACQ_Viper650(H.data));
2337 
2338  CatchPrint();
2339  if (TryStt < 0) {
2340  vpERROR_TRACE("Cannot get the force/torque measures.");
2341  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2342  }
2343 }
2344 
2384 {
2385  InitTry;
2386 
2387  vpColVector H(6);
2388 
2389  Try(PrimitiveTFS_ACQ_Viper650(H.data));
2390 
2391  return H;
2392 
2393  CatchPrint();
2394  if (TryStt < 0) {
2395  vpERROR_TRACE("Cannot get the force/torque measures.");
2396  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2397  }
2398  return H; // Here to avoid a warning, but should never be called
2399 }
2400 
2407 {
2408  InitTry;
2409  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
2410  std::cout << "Enable joint limits on axis 6..." << std::endl;
2411  CatchPrint();
2412  if (TryStt < 0) {
2413  vpERROR_TRACE("Cannot enable joint limits on axis 6");
2414  throw vpRobotException(vpRobotException::lowLevelError, "Cannot enable joint limits on axis 6.");
2415  }
2416 }
2417 
2429 {
2430  InitTry;
2431  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1));
2432  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2433  CatchPrint();
2434  if (TryStt < 0) {
2435  vpERROR_TRACE("Cannot disable joint limits on axis 6");
2436  throw vpRobotException(vpRobotException::lowLevelError, "Cannot disable joint limits on axis 6.");
2437  }
2438 }
2439 
2449 {
2452 
2453  return;
2454 }
2455 
2476 {
2477  maxRotationVelocity_joint6 = w6_max;
2478  return;
2479 }
2480 
2488 double vpRobotViper650::getMaxRotationVelocityJoint6() const { return maxRotationVelocity_joint6; }
2489 
2497 {
2498  InitTry;
2499  Try(PrimitivePneumaticGripper_Viper650(1));
2500  std::cout << "Open the pneumatic gripper..." << std::endl;
2501  CatchPrint();
2502  if (TryStt < 0) {
2503  throw vpRobotException(vpRobotException::lowLevelError, "Cannot open the gripper.");
2504  }
2505 }
2506 
2515 {
2516  InitTry;
2517  Try(PrimitivePneumaticGripper_Viper650(0));
2518  std::cout << "Close the pneumatic gripper..." << std::endl;
2519  CatchPrint();
2520  if (TryStt < 0) {
2521  throw vpRobotException(vpRobotException::lowLevelError, "Cannot close the gripper.");
2522  }
2523 }
2524 
2525 #elif !defined(VISP_BUILD_SHARED_LIBS)
2526 // Work arround to avoid warning: libvisp_robot.a(vpRobotViper650.cpp.o) has
2527 // no symbols
2528 void dummy_vpRobotViper650(){};
2529 #endif
static const double defaultPositioningVelocity
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
Error that can be emited by the vpRobot class and its derivates.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1159
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
virtual ~vpRobotViper650(void)
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
void setPositioningVelocity(const double velocity)
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:251
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper650.h:176
double maxRotationVelocity
Definition: vpRobot.h:93
void setMaxRotationVelocityJoint6(double w6_max)
Initialize the position controller.
Definition: vpRobot.h:68
vpHomogeneousMatrix inverse() const
vpRowVector t() const
Class that defines a generic virtual robot.
Definition: vpRobot.h:58
Automatic control mode (default).
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 setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:273
void extract(vpRotationMatrix &R) const
static bool savePosFile(const std::string &filename, const vpColVector &q)
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
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.
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:600
void biasForceTorqueSensor() const
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper650.h:136
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
Initialize the velocity controller.
Definition: vpRobot.h:67
Emergency stop activated.
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:139
vpRobotStateType
Definition: vpRobot.h:64
bool getPowerState() const
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
Modelisation of the ADEPT Viper 650 robot.
Definition: vpViper650.h:102
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:563
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 init(void)
Definition: vpViper650.cpp:135
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:127
static double rad(double deg)
Definition: vpMath.h:102
void enableJoint6Limits() const
void get_fJe(vpMatrix &fJe)
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:260
double getPositioningVelocity(void) const
static double deg(double rad)
Definition: vpMath.h:95
double getTime() const
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition: vpRobot.h:99
vpColVector getForceTorque() const
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:92
void move(const std::string &filename)
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:156
void disableJoint6Limits() const
void setMaxRotationVelocity(double w_max)
static bool readPosFile(const std::string &filename, vpColVector &q)
void get_cMe(vpHomogeneousMatrix &cMe) const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRzyzVector.h:154
void get_cVe(vpVelocityTwistMatrix &cVe) const
double getMaxRotationVelocityJoint6() const
void closeGripper() const
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
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 get_eJe(vpMatrix &eJe)
void set_eMc(const vpHomogeneousMatrix &eMc_)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:241
vpColVector joint_min
Definition: vpViper.h:173