Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpRobotViper650.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 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 https://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 *****************************************************************************/
35 
36 #include <visp3/core/vpConfig.h>
37 
38 #ifdef VISP_HAVE_VIPER650
39 
40 #include <signal.h>
41 #include <stdlib.h>
42 #include <sys/types.h>
43 #include <unistd.h>
44 
45 #include <visp3/core/vpDebug.h>
46 #include <visp3/core/vpExponentialMap.h>
47 #include <visp3/core/vpIoTools.h>
48 #include <visp3/core/vpThetaUVector.h>
49 #include <visp3/core/vpVelocityTwistMatrix.h>
50 #include <visp3/robot/vpRobot.h>
51 #include <visp3/robot/vpRobotException.h>
52 #include <visp3/robot/vpRobotViper650.h>
53 
55 /* ---------------------------------------------------------------------- */
56 /* --- STATIC ----------------------------------------------------------- */
57 /* ---------------------------------------------------------------------- */
58 
59 bool vpRobotViper650::m_robotAlreadyCreated = false;
60 
69 
70 /* ---------------------------------------------------------------------- */
71 /* --- EMERGENCY STOP --------------------------------------------------- */
72 /* ---------------------------------------------------------------------- */
73 
81 void emergencyStopViper650(int signo)
82 {
83  std::cout << "Stop the Viper650 application by signal (" << signo << "): " << (char)7;
84  switch (signo) {
85  case SIGINT:
86  std::cout << "SIGINT (stop by ^C) " << std::endl;
87  break;
88  case SIGBUS:
89  std::cout << "SIGBUS (stop due to a bus error) " << std::endl;
90  break;
91  case SIGSEGV:
92  std::cout << "SIGSEGV (stop due to a segmentation fault) " << std::endl;
93  break;
94  case SIGKILL:
95  std::cout << "SIGKILL (stop by CTRL \\) " << std::endl;
96  break;
97  case SIGQUIT:
98  std::cout << "SIGQUIT " << std::endl;
99  break;
100  default:
101  std::cout << signo << std::endl;
102  }
103  // std::cout << "Emergency stop called\n";
104  // PrimitiveESTOP_Viper650();
105  PrimitiveSTOP_Viper650();
106  std::cout << "Robot was stopped\n";
107 
108  // Free allocated resources
109  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
110 
111  fprintf(stdout, "Application ");
112  fflush(stdout);
113  kill(getpid(), SIGKILL);
114  exit(1);
115 }
116 
117 /* ---------------------------------------------------------------------- */
118 /* --- CONSTRUCTOR ------------------------------------------------------ */
119 /* ---------------------------------------------------------------------- */
120 
179 vpRobotViper650::vpRobotViper650(bool verbose) : vpViper650(), vpRobot()
180 {
181 
182  /*
183  #define SIGHUP 1 // hangup
184  #define SIGINT 2 // interrupt (rubout)
185  #define SIGQUIT 3 // quit (ASCII FS)
186  #define SIGILL 4 // illegal instruction (not reset when caught)
187  #define SIGTRAP 5 // trace trap (not reset when caught)
188  #define SIGIOT 6 // IOT instruction
189  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
190  #define SIGEMT 7 // EMT instruction
191  #define SIGFPE 8 // floating point exception
192  #define SIGKILL 9 // kill (cannot be caught or ignored)
193  #define SIGBUS 10 // bus error
194  #define SIGSEGV 11 // segmentation violation
195  #define SIGSYS 12 // bad argument to system call
196  #define SIGPIPE 13 // write on a pipe with no one to read it
197  #define SIGALRM 14 // alarm clock
198  #define SIGTERM 15 // software termination signal from kill
199  */
200 
201  signal(SIGINT, emergencyStopViper650);
202  signal(SIGBUS, emergencyStopViper650);
203  signal(SIGSEGV, emergencyStopViper650);
204  signal(SIGKILL, emergencyStopViper650);
205  signal(SIGQUIT, emergencyStopViper650);
206 
207  setVerbose(verbose);
208  if (verbose_)
209  std::cout << "Open communication with MotionBlox.\n";
210  try {
211  this->init();
213  }
214  catch (...) {
215  // vpERROR_TRACE("Error caught") ;
216  throw;
217  }
218  m_positioningVelocity = m_defaultPositioningVelocity;
219 
220  m_maxRotationVelocity_joint6 = maxRotationVelocity;
221 
222  vpRobotViper650::m_robotAlreadyCreated = true;
223 
224  return;
225 }
226 
227 /* ------------------------------------------------------------------------ */
228 /* --- INITIALISATION ----------------------------------------------------- */
229 /* ------------------------------------------------------------------------ */
230 
254 {
255  InitTry;
256 
257  // Initialise private variables used to compute the measured velocities
258  m_q_prev_getvel.resize(6);
259  m_q_prev_getvel = 0;
260  m_time_prev_getvel = 0;
261  m_first_time_getvel = true;
262 
263  // Initialise private variables used to compute the measured displacement
264  m_q_prev_getdis.resize(6);
265  m_q_prev_getdis = 0;
266  m_first_time_getdis = true;
267 
268  // Initialize the firewire connection
269  Try(InitializeConnection(verbose_));
270 
271  // Connect to the servoboard using the servo board GUID
272  Try(InitializeNode_Viper650());
273 
274  Try(PrimitiveRESET_Viper650());
275 
276  // Enable the joint limits on axis 6
277  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
278 
279  // Update the eMc matrix in the low level controller
281 
282  // Look if the power is on or off
283  UInt32 HIPowerStatus;
284  UInt32 EStopStatus;
285  Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
286  CAL_Wait(0.1);
287 
288  // Print the robot status
289  if (verbose_) {
290  std::cout << "Robot status: ";
291  switch (EStopStatus) {
292  case ESTOP_AUTO:
293  m_controlMode = AUTO;
294  if (HIPowerStatus == 0)
295  std::cout << "Power is OFF" << std::endl;
296  else
297  std::cout << "Power is ON" << std::endl;
298  break;
299 
300  case ESTOP_MANUAL:
301  m_controlMode = MANUAL;
302  if (HIPowerStatus == 0)
303  std::cout << "Power is OFF" << std::endl;
304  else
305  std::cout << "Power is ON" << std::endl;
306  break;
307  case ESTOP_ACTIVATED:
308  m_controlMode = ESTOP;
309  std::cout << "Emergency stop is activated" << std::endl;
310  break;
311  default:
312  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
313  std::cout << "You have to call Adept for maintenance..." << std::endl;
314  // Free allocated resources
315  }
316  std::cout << std::endl;
317  }
318  // get real joint min/max from the MotionBlox
319  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
320  // Convert units from degrees to radians
321  joint_min.deg2rad();
322  joint_max.deg2rad();
323 
324  // for (unsigned int i=0; i < njoint; i++) {
325  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
326  // joint_max[i]);
327  // }
328 
329  // If an error occur in the low level controller, goto here
330  // CatchPrint();
331  Catch();
332 
333  // Test if an error occurs
334  if (TryStt == -20001)
335  printf("No connection detected. Check if the robot is powered on \n"
336  "and if the firewire link exist between the MotionBlox and this "
337  "computer.\n");
338  else if (TryStt == -675)
339  printf(" Timeout enabling power...\n");
340 
341  if (TryStt < 0) {
342  // Power off the robot
343  PrimitivePOWEROFF_Viper650();
344  // Free allocated resources
345  ShutDownConnection();
346 
347  std::cout << "Cannot open connection with the motionblox..." << std::endl;
348  throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with the motionblox");
349  }
350  return;
351 }
352 
414 {
415  // Read the robot constants from files
416  // - joint [min,max], coupl_56, long_56
417  // - camera extrinsic parameters relative to eMc
419 
420  InitTry;
421 
422  // Get real joint min/max from the MotionBlox
423  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
424  // Convert units from degrees to radians
425  joint_min.deg2rad();
426  joint_max.deg2rad();
427 
428  // for (unsigned int i=0; i < njoint; i++) {
429  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
430  // joint_max[i]);
431  // }
432 
433  // Set the camera constant (eMc pose) in the MotionBlox
434  double eMc_pose[6];
435  for (unsigned int i = 0; i < 3; i++) {
436  eMc_pose[i] = etc[i]; // translation in meters
437  eMc_pose[i + 3] = erc[i]; // rotation in rad
438  }
439  // Update the eMc pose in the low level controller
440  Try(PrimitiveCONST_Viper650(eMc_pose));
441 
442  CatchPrint();
443  return;
444 }
445 
500 void vpRobotViper650::init(vpViper650::vpToolType tool, const std::string &filename)
501 {
502  vpViper650::init(tool, filename);
503 
504  InitTry;
505 
506  // Get real joint min/max from the MotionBlox
507  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
508  // Convert units from degrees to radians
509  joint_min.deg2rad();
510  joint_max.deg2rad();
511 
512  // for (unsigned int i=0; i < njoint; i++) {
513  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
514  // joint_max[i]);
515  // }
516 
517  // Set the camera constant (eMc pose) in the MotionBlox
518  double eMc_pose[6];
519  for (unsigned int i = 0; i < 3; i++) {
520  eMc_pose[i] = etc[i]; // translation in meters
521  eMc_pose[i + 3] = erc[i]; // rotation in rad
522  }
523  // Update the eMc pose in the low level controller
524  Try(PrimitiveCONST_Viper650(eMc_pose));
525 
526  CatchPrint();
527  return;
528 }
529 
571 {
572  vpViper650::init(tool, eMc_);
573 
574  InitTry;
575 
576  // Get real joint min/max from the MotionBlox
577  Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
578  // Convert units from degrees to radians
579  joint_min.deg2rad();
580  joint_max.deg2rad();
581 
582  // for (unsigned int i=0; i < njoint; i++) {
583  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
584  // joint_max[i]);
585  // }
586 
587  // Set the camera constant (eMc pose) in the MotionBlox
588  double eMc_pose[6];
589  for (unsigned int i = 0; i < 3; i++) {
590  eMc_pose[i] = etc[i]; // translation in meters
591  eMc_pose[i + 3] = erc[i]; // rotation in rad
592  }
593  // Update the eMc pose in the low level controller
594  Try(PrimitiveCONST_Viper650(eMc_pose));
595 
596  CatchPrint();
597  return;
598 }
599 
612 {
613  this->vpViper650::set_eMc(eMc_);
614 
615  InitTry;
616 
617  // Set the camera constant (eMc pose) in the MotionBlox
618  double eMc_pose[6];
619  for (unsigned int i = 0; i < 3; i++) {
620  eMc_pose[i] = etc[i]; // translation in meters
621  eMc_pose[i + 3] = erc[i]; // rotation in rad
622  }
623  // Update the eMc pose in the low level controller
624  Try(PrimitiveCONST_Viper650(eMc_pose));
625 
626  CatchPrint();
627 
628  return;
629 }
630 
644 {
645  this->vpViper650::set_eMc(etc_, erc_);
646 
647  InitTry;
648 
649  // Set the camera constant (eMc pose) in the MotionBlox
650  double eMc_pose[6];
651  for (unsigned int i = 0; i < 3; i++) {
652  eMc_pose[i] = etc[i]; // translation in meters
653  eMc_pose[i + 3] = erc[i]; // rotation in rad
654  }
655  // Update the eMc pose in the low level controller
656  Try(PrimitiveCONST_Viper650(eMc_pose));
657 
658  CatchPrint();
659 
660  return;
661 }
662 
663 /* ------------------------------------------------------------------------ */
664 /* --- DESTRUCTOR --------------------------------------------------------- */
665 /* ------------------------------------------------------------------------ */
666 
674 {
675  InitTry;
676 
678 
679  // Look if the power is on or off
680  UInt32 HIPowerStatus;
681  Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
682  CAL_Wait(0.1);
683 
684  // if (HIPowerStatus == 1) {
685  // fprintf(stdout, "Power OFF the robot\n");
686  // fflush(stdout);
687 
688  // Try( PrimitivePOWEROFF_Viper650() );
689  // }
690 
691  // Free allocated resources
692  ShutDownConnection();
693 
694  vpRobotViper650::m_robotAlreadyCreated = false;
695 
696  CatchPrint();
697  return;
698 }
699 
707 {
708  InitTry;
709 
710  switch (newState) {
711  case vpRobot::STATE_STOP: {
712  // Start primitive STOP only if the current state is Velocity
714  Try(PrimitiveSTOP_Viper650());
715  vpTime::sleepMs(100); // needed to ensure velocity task ends up on low level
716  }
717  break;
718  }
721  std::cout << "Change the control mode from velocity to position control.\n";
722  Try(PrimitiveSTOP_Viper650());
723  }
724  else {
725  // std::cout << "Change the control mode from stop to position
726  // control.\n";
727  }
728  this->powerOn();
729  break;
730  }
733  std::cout << "Change the control mode from stop to velocity control.\n";
734  }
735  this->powerOn();
736  break;
737  }
738  default:
739  break;
740  }
741 
742  CatchPrint();
743 
744  return vpRobot::setRobotState(newState);
745 }
746 
747 /* ------------------------------------------------------------------------ */
748 /* --- STOP --------------------------------------------------------------- */
749 /* ------------------------------------------------------------------------ */
750 
759 {
761  return;
762 
763  InitTry;
764  Try(PrimitiveSTOP_Viper650());
766 
767  CatchPrint();
768  if (TryStt < 0) {
769  vpERROR_TRACE("Cannot stop robot motion");
770  throw vpRobotException(vpRobotException::lowLevelError, "Cannot stop robot motion.");
771  }
772 }
773 
784 {
785  InitTry;
786 
787  // Look if the power is on or off
788  UInt32 HIPowerStatus;
789  UInt32 EStopStatus;
790  bool firsttime = true;
791  unsigned int nitermax = 10;
792 
793  for (unsigned int i = 0; i < nitermax; i++) {
794  Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
795  if (EStopStatus == ESTOP_AUTO) {
796  m_controlMode = AUTO;
797  break; // exit for loop
798  }
799  else if (EStopStatus == ESTOP_MANUAL) {
800  m_controlMode = MANUAL;
801  break; // exit for loop
802  }
803  else if (EStopStatus == ESTOP_ACTIVATED) {
804  m_controlMode = ESTOP;
805  if (firsttime) {
806  std::cout << "Emergency stop is activated! \n"
807  << "Check the emergency stop button and push the yellow "
808  "button before continuing."
809  << std::endl;
810  firsttime = false;
811  }
812  fprintf(stdout, "Remaining time %us \r", nitermax - i);
813  fflush(stdout);
814  CAL_Wait(1);
815  }
816  else {
817  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
818  std::cout << "You have to call Adept for maintenance..." << std::endl;
819  // Free allocated resources
820  ShutDownConnection();
821  throw(vpRobotException(vpRobotException::lowLevelError, "Error on the emergency chain"));
822  }
823  }
824 
825  if (EStopStatus == ESTOP_ACTIVATED)
826  std::cout << std::endl;
827 
828  if (EStopStatus == ESTOP_ACTIVATED) {
829  std::cout << "Sorry, cannot power on the robot." << std::endl;
830  throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power on the robot."));
831  }
832 
833  if (HIPowerStatus == 0) {
834  fprintf(stdout, "Power ON the Viper650 robot\n");
835  fflush(stdout);
836 
837  Try(PrimitivePOWERON_Viper650());
838  }
839 
840  CatchPrint();
841  if (TryStt < 0) {
842  vpERROR_TRACE("Cannot power on the robot");
843  throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot."));
844  }
845 }
846 
857 {
858  InitTry;
859 
860  // Look if the power is on or off
861  UInt32 HIPowerStatus;
862  Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
863  CAL_Wait(0.1);
864 
865  if (HIPowerStatus == 1) {
866  fprintf(stdout, "Power OFF the Viper650 robot\n");
867  fflush(stdout);
868 
869  Try(PrimitivePOWEROFF_Viper650());
870  }
871 
872  CatchPrint();
873  if (TryStt < 0) {
874  vpERROR_TRACE("Cannot power off the robot");
875  throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
876  }
877 }
878 
891 {
892  InitTry;
893  bool status = false;
894  // Look if the power is on or off
895  UInt32 HIPowerStatus;
896  Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
897  CAL_Wait(0.1);
898 
899  if (HIPowerStatus == 1) {
900  status = true;
901  }
902 
903  CatchPrint();
904  if (TryStt < 0) {
905  vpERROR_TRACE("Cannot get the power status");
906  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get the power status.");
907  }
908  return status;
909 }
910 
921 {
923  vpViper650::get_cMe(cMe);
924 
925  cVe.build(cMe);
926 }
927 
940 
953 {
954 
955  double position[6];
956  double timestamp;
957 
958  InitTry;
959  Try(PrimitiveACQ_POS_J_Viper650(position, &timestamp));
960  CatchPrint();
961 
962  vpColVector q(6);
963  for (unsigned int i = 0; i < njoint; i++)
964  q[i] = vpMath::rad(position[i]);
965 
966  try {
968  }
969  catch (...) {
970  vpERROR_TRACE("catch exception ");
971  throw;
972  }
973 }
987 {
988 
989  double position[6];
990  double timestamp;
991 
992  InitTry;
993  Try(PrimitiveACQ_POS_Viper650(position, &timestamp));
994  CatchPrint();
995 
996  vpColVector q(6);
997  for (unsigned int i = 0; i < njoint; i++)
998  q[i] = position[i];
999 
1000  try {
1002  }
1003  catch (...) {
1004  vpERROR_TRACE("Error caught");
1005  throw;
1006  }
1007 }
1008 
1049 void vpRobotViper650::setPositioningVelocity(double velocity) { m_positioningVelocity = velocity; }
1050 
1056 double vpRobotViper650::getPositioningVelocity(void) const { return m_positioningVelocity; }
1057 
1139 {
1140 
1142  vpERROR_TRACE("Robot was not in position-based control\n"
1143  "Modification of the robot state");
1145  }
1146 
1147  vpColVector destination(njoint);
1148  int error = 0;
1149  double timestamp;
1150 
1151  InitTry;
1152  switch (frame) {
1153  case vpRobot::CAMERA_FRAME: {
1154  vpColVector q(njoint);
1155  Try(PrimitiveACQ_POS_Viper650(q.data, &timestamp));
1156 
1157  // Convert degrees into rad
1158  q.deg2rad();
1159 
1160  // Get fMc from the inverse kinematics
1161  vpHomogeneousMatrix fMc;
1162  vpViper650::get_fMc(q, fMc);
1163 
1164  // Set cMc from the input position
1165  vpTranslationVector txyz;
1166  vpRxyzVector rxyz;
1167  for (unsigned int i = 0; i < 3; i++) {
1168  txyz[i] = position[i];
1169  rxyz[i] = position[i + 3];
1170  }
1171 
1172  // Compute cMc2
1173  vpRotationMatrix cRc2(rxyz);
1174  vpHomogeneousMatrix cMc2(txyz, cRc2);
1175 
1176  // Compute the new position to reach: fMc*cMc2
1177  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1178 
1179  // Compute the corresponding joint position from the inverse kinematics
1180  unsigned int solution = this->getInverseKinematics(fMc2, q);
1181  if (solution) { // Position is reachable
1182  destination = q;
1183  // convert rad to deg requested for the low level controller
1184  destination.rad2deg();
1185  Try(PrimitiveMOVE_J_Viper650(destination.data, m_positioningVelocity));
1186  Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1187  }
1188  else {
1189  // Cartesian position is out of range
1190  error = -1;
1191  }
1192 
1193  break;
1194  }
1195  case vpRobot::ARTICULAR_FRAME: {
1196  destination = position;
1197  // convert rad to deg requested for the low level controller
1198  destination.rad2deg();
1199 
1200  // std::cout << "Joint destination (deg): " << destination.t() <<
1201  // std::endl;
1202  Try(PrimitiveMOVE_J_Viper650(destination.data, m_positioningVelocity));
1203  Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1204  break;
1205  }
1206  case vpRobot::REFERENCE_FRAME: {
1207  // Convert angles from Rxyz representation to Rzyz representation
1208  vpRxyzVector rxyz(position[3], position[4], position[5]);
1209  vpRotationMatrix R(rxyz);
1210  vpRzyzVector rzyz(R);
1211 
1212  for (unsigned int i = 0; i < 3; i++) {
1213  destination[i] = position[i];
1214  destination[i + 3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1215  }
1216  int configuration = 0; // keep the actual configuration
1217 
1218  // std::cout << "Base frame destination Rzyz (deg): " << destination.t()
1219  // << std::endl;
1220  Try(PrimitiveMOVE_C_Viper650(destination.data, configuration, m_positioningVelocity));
1221  Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1222 
1223  break;
1224  }
1225  case vpRobot::MIXT_FRAME: {
1226  throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1227  "Mixt frame not implemented.");
1228  }
1230  throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1231  "Mixt frame not implemented.");
1232  }
1233  }
1234 
1235  CatchPrint();
1236  if (TryStt == InvalidPosition || TryStt == -1023)
1237  std::cout << " : Position out of range.\n";
1238 
1239  else if (TryStt == -3019) {
1240  if (frame == vpRobot::ARTICULAR_FRAME)
1241  std::cout << " : Joint position out of range.\n";
1242  else
1243  std::cout << " : Cartesian position leads to a joint position out of "
1244  "range.\n";
1245  }
1246  else if (TryStt < 0)
1247  std::cout << " : Unknown error (see Fabien).\n";
1248  else if (error == -1)
1249  std::cout << "Position out of range.\n";
1250 
1251  if (TryStt < 0 || error < 0) {
1252  vpERROR_TRACE("Positioning error.");
1253  throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1254  }
1255 
1256  return;
1257 }
1258 
1327 void vpRobotViper650::setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3,
1328  double pos4, double pos5, double pos6)
1329 {
1330  try {
1331  vpColVector position(6);
1332  position[0] = pos1;
1333  position[1] = pos2;
1334  position[2] = pos3;
1335  position[3] = pos4;
1336  position[4] = pos5;
1337  position[5] = pos6;
1338 
1339  setPosition(frame, position);
1340  }
1341  catch (...) {
1342  vpERROR_TRACE("Error caught");
1343  throw;
1344  }
1345 }
1346 
1389 void vpRobotViper650::setPosition(const std::string &filename)
1390 {
1391  vpColVector q;
1392  bool ret;
1393 
1394  ret = this->readPosFile(filename, q);
1395 
1396  if (ret == false) {
1397  vpERROR_TRACE("Bad position in \"%s\"", filename.c_str());
1398  throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1399  }
1402 }
1403 
1475 void vpRobotViper650::getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp)
1476 {
1477 
1478  InitTry;
1479 
1480  position.resize(6);
1481 
1482  switch (frame) {
1483  case vpRobot::CAMERA_FRAME: {
1484  position = 0;
1485  return;
1486  }
1487  case vpRobot::ARTICULAR_FRAME: {
1488  Try(PrimitiveACQ_POS_J_Viper650(position.data, &timestamp));
1489  // vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1490  position.deg2rad();
1491 
1492  return;
1493  }
1494  case vpRobot::REFERENCE_FRAME: {
1495  vpColVector q(njoint);
1496  Try(PrimitiveACQ_POS_J_Viper650(q.data, &timestamp));
1497 
1498  // Compute fMc
1500 
1501  // From fMc extract the pose
1502  vpRotationMatrix fRc;
1503  fMc.extract(fRc);
1504  vpRxyzVector rxyz;
1505  rxyz.build(fRc);
1506 
1507  for (unsigned int i = 0; i < 3; i++) {
1508  position[i] = fMc[i][3]; // translation x,y,z
1509  position[i + 3] = rxyz[i]; // Euler rotation x,y,z
1510  }
1511 
1512  break;
1513  }
1514  case vpRobot::MIXT_FRAME: {
1515  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
1516  "not implemented");
1517  }
1519  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in end-effector frame: "
1520  "not implemented");
1521  }
1522  }
1523 
1524  CatchPrint();
1525  if (TryStt < 0) {
1526  vpERROR_TRACE("Cannot get position.");
1527  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position.");
1528  }
1529 
1530  return;
1531 }
1532 
1544 {
1545  double timestamp;
1546  getPosition(frame, position, timestamp);
1547 }
1548 
1562 void vpRobotViper650::getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
1563 {
1564  vpColVector posRxyz;
1565  // recupere position en Rxyz
1566  this->getPosition(frame, posRxyz, timestamp);
1567  vpRxyzVector RxyzVect;
1568  for (unsigned int j = 0; j < 3; j++)
1569  RxyzVect[j] = posRxyz[j + 3];
1570  // recupere le vecteur thetaU correspondant
1571  vpThetaUVector RtuVect(RxyzVect);
1572 
1573  // remplit le vpPoseVector avec translation et rotation ThetaU
1574  for (unsigned int j = 0; j < 3; j++) {
1575  position[j] = posRxyz[j];
1576  position[j + 3] = RtuVect[j];
1577  }
1578 }
1579 
1591 {
1592  double timestamp;
1593  getPosition(frame, position, timestamp);
1594 }
1595 
1601 {
1602  double timestamp;
1603  PrimitiveACQ_TIME_Viper650(&timestamp);
1604  return timestamp;
1605 }
1606 
1689 {
1691  vpERROR_TRACE("Cannot send a velocity to the robot "
1692  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1694  "Cannot send a velocity to the robot "
1695  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1696  }
1697 
1698  vpColVector vel_sat(6);
1699 
1700  // Velocity saturation
1701  switch (frame) {
1702  // saturation in cartesian space
1703  case vpRobot::CAMERA_FRAME:
1706  case vpRobot::MIXT_FRAME: {
1707  vpColVector vel_max(6);
1708 
1709  for (unsigned int i = 0; i < 3; i++)
1710  vel_max[i] = getMaxTranslationVelocity();
1711  for (unsigned int i = 3; i < 6; i++)
1712  vel_max[i] = getMaxRotationVelocity();
1713 
1714  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1715 
1716  break;
1717  }
1718  // saturation in joint space
1719  case vpRobot::ARTICULAR_FRAME: {
1720  vpColVector vel_max(6);
1721 
1722  // if (getMaxRotationVelocity() == getMaxRotationVelocityJoint6()) {
1723  if (std::fabs(getMaxRotationVelocity() - getMaxRotationVelocityJoint6()) < std::numeric_limits<double>::epsilon()) {
1724  for (unsigned int i = 0; i < 6; i++)
1725  vel_max[i] = getMaxRotationVelocity();
1726  }
1727  else {
1728  for (unsigned int i = 0; i < 5; i++)
1729  vel_max[i] = getMaxRotationVelocity();
1730  vel_max[5] = getMaxRotationVelocityJoint6();
1731  }
1732 
1733  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1734  }
1735  }
1736 
1737  InitTry;
1738 
1739  switch (frame) {
1740  case vpRobot::CAMERA_FRAME: {
1741  // Send velocities in m/s and rad/s
1742  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1743  Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPCAM_VIPER650));
1744  break;
1745  }
1747  // Transform in camera frame
1748  vpHomogeneousMatrix cMe;
1749  this->get_cMe(cMe);
1750  vpVelocityTwistMatrix cVe(cMe);
1751  vpColVector v_c = cVe * vel_sat;
1752  // Send velocities in m/s and rad/s
1753  Try(PrimitiveMOVESPEED_CART_Viper650(v_c.data, REPCAM_VIPER650));
1754  break;
1755  }
1756  case vpRobot::ARTICULAR_FRAME: {
1757  // Convert all the velocities from rad/s into deg/s
1758  vel_sat.rad2deg();
1759  // std::cout << "Vitesse appliquee: " << vel_sat.t();
1760  // Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER650) );
1761  Try(PrimitiveMOVESPEED_Viper650(vel_sat.data));
1762  break;
1763  }
1764  case vpRobot::REFERENCE_FRAME: {
1765  // Send velocities in m/s and rad/s
1766  // std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1767  Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPFIX_VIPER650));
1768  break;
1769  }
1770  case vpRobot::MIXT_FRAME: {
1771  // Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPMIX_VIPER650) );
1772  break;
1773  }
1774  default: {
1775  vpERROR_TRACE("Error in spec of vpRobot. "
1776  "Case not taken in account.");
1777  return;
1778  }
1779  }
1780 
1781  Catch();
1782  if (TryStt < 0) {
1783  if (TryStt == VelStopOnJoint) {
1784  UInt32 axisInJoint[njoint];
1785  PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr);
1786  for (unsigned int i = 0; i < njoint; i++) {
1787  if (axisInJoint[i])
1788  std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl;
1789  }
1790  }
1791  else {
1792  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1793  if (TryString != nullptr) {
1794  // The statement is in TryString, but we need to check the validity
1795  printf(" Error sentence %s\n", TryString); // Print the TryString
1796  }
1797  else {
1798  printf("\n");
1799  }
1800  }
1801  }
1802 
1803  return;
1804 }
1805 
1806 /* ------------------------------------------------------------------------ */
1807 /* --- GET ---------------------------------------------------------------- */
1808 /* ------------------------------------------------------------------------ */
1809 
1870 void vpRobotViper650::getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp)
1871 {
1872  velocity.resize(6);
1873  velocity = 0;
1874 
1875  vpColVector q_cur(6);
1876  vpHomogeneousMatrix fMe_cur, fMc_cur;
1877  vpHomogeneousMatrix eMe, cMc; // camera displacement
1878  double time_cur;
1879 
1880  InitTry;
1881 
1882  // Get the current joint position
1883  Try(PrimitiveACQ_POS_J_Viper650(q_cur.data, &timestamp));
1884  time_cur = timestamp;
1885  q_cur.deg2rad();
1886 
1887  // Get the end-effector pose from the direct kinematics
1888  vpViper650::get_fMe(q_cur, fMe_cur);
1889  // Get the camera pose from the direct kinematics
1890  vpViper650::get_fMc(q_cur, fMc_cur);
1891 
1892  if (!m_first_time_getvel) {
1893 
1894  switch (frame) {
1896  // Compute the displacement of the end-effector since the previous call
1897  eMe = m_fMe_prev_getvel.inverse() * fMe_cur;
1898 
1899  // Compute the velocity of the end-effector from this displacement
1900  velocity = vpExponentialMap::inverse(eMe, time_cur - m_time_prev_getvel);
1901 
1902  break;
1903  }
1904 
1905  case vpRobot::CAMERA_FRAME: {
1906  // Compute the displacement of the camera since the previous call
1907  cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1908 
1909  // Compute the velocity of the camera from this displacement
1910  velocity = vpExponentialMap::inverse(cMc, time_cur - m_time_prev_getvel);
1911 
1912  break;
1913  }
1914 
1915  case vpRobot::ARTICULAR_FRAME: {
1916  velocity = (q_cur - m_q_prev_getvel) / (time_cur - m_time_prev_getvel);
1917  break;
1918  }
1919 
1920  case vpRobot::REFERENCE_FRAME: {
1921  // Compute the displacement of the camera since the previous call
1922  cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1923 
1924  // Compute the velocity of the camera from this displacement
1925  vpColVector v;
1926  v = vpExponentialMap::inverse(cMc, time_cur - m_time_prev_getvel);
1927 
1928  // Express this velocity in the reference frame
1929  vpVelocityTwistMatrix fVc(fMc_cur);
1930  velocity = fVc * v;
1931 
1932  break;
1933  }
1934 
1935  case vpRobot::MIXT_FRAME: {
1936  // Compute the displacement of the camera since the previous call
1937  cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1938 
1939  // Compute the ThetaU representation for the rotation
1940  vpRotationMatrix cRc;
1941  cMc.extract(cRc);
1942  vpThetaUVector thetaU;
1943  thetaU.build(cRc);
1944 
1945  for (unsigned int i = 0; i < 3; i++) {
1946  // Compute the translation displacement in the reference frame
1947  velocity[i] = m_fMc_prev_getvel[i][3] - fMc_cur[i][3];
1948  // Update the rotation displacement in the camera frame
1949  velocity[i + 3] = thetaU[i];
1950  }
1951 
1952  // Compute the velocity
1953  velocity /= (time_cur - m_time_prev_getvel);
1954  break;
1955  }
1956  default: {
1958  "vpRobotViper650::getVelocity() not implemented in end-effector"));
1959  }
1960  }
1961  }
1962  else {
1963  m_first_time_getvel = false;
1964  }
1965 
1966  // Memorize the end-effector pose for the next call
1967  m_fMe_prev_getvel = fMe_cur;
1968  // Memorize the camera pose for the next call
1969  m_fMc_prev_getvel = fMc_cur;
1970 
1971  // Memorize the joint position for the next call
1972  m_q_prev_getvel = q_cur;
1973 
1974  // Memorize the time associated to the joint position for the next call
1975  m_time_prev_getvel = time_cur;
1976 
1977  CatchPrint();
1978  if (TryStt < 0) {
1979  vpERROR_TRACE("Cannot get velocity.");
1980  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
1981  }
1982 }
1983 
1993 {
1994  double timestamp;
1995  getVelocity(frame, velocity, timestamp);
1996 }
1997 
2052 {
2053  vpColVector velocity;
2054  getVelocity(frame, velocity, timestamp);
2055 
2056  return velocity;
2057 }
2058 
2068 {
2069  vpColVector velocity;
2070  double timestamp;
2071  getVelocity(frame, velocity, timestamp);
2072 
2073  return velocity;
2074 }
2075 
2145 bool vpRobotViper650::readPosFile(const std::string &filename, vpColVector &q)
2146 {
2147  std::ifstream fd(filename.c_str(), std::ios::in);
2148 
2149  if (!fd.is_open()) {
2150  return false;
2151  }
2152 
2153  std::string line;
2154  std::string key("R:");
2155  std::string id("#Viper650 - Position");
2156  bool pos_found = false;
2157  int lineNum = 0;
2158 
2159  q.resize(njoint);
2160 
2161  while (std::getline(fd, line)) {
2162  lineNum++;
2163  if (lineNum == 1) {
2164  if (!(line.compare(0, id.size(), id) == 0)) { // check if Viper650 position file
2165  std::cout << "Error: this position file " << filename << " is not for Viper650 robot" << std::endl;
2166  return false;
2167  }
2168  }
2169  if ((line.compare(0, 1, "#") == 0)) { // skip comment
2170  continue;
2171  }
2172  if ((line.compare(0, key.size(), key) == 0)) { // decode position
2173  // check if there are at least njoint values in the line
2174  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2175  if (chain.size() < njoint + 1) // try to split with tab separator
2176  chain = vpIoTools::splitChain(line, std::string("\t"));
2177  if (chain.size() < njoint + 1)
2178  continue;
2179 
2180  std::istringstream ss(line);
2181  std::string key_;
2182  ss >> key_;
2183  for (unsigned int i = 0; i < njoint; i++)
2184  ss >> q[i];
2185  pos_found = true;
2186  break;
2187  }
2188  }
2189 
2190  // converts rotations from degrees into radians
2191  q.deg2rad();
2192 
2193  fd.close();
2194 
2195  if (!pos_found) {
2196  std::cout << "Error: unable to find a position for Viper650 robot in " << filename << std::endl;
2197  return false;
2198  }
2199 
2200  return true;
2201 }
2202 
2226 bool vpRobotViper650::savePosFile(const std::string &filename, const vpColVector &q)
2227 {
2228 
2229  FILE *fd;
2230  fd = fopen(filename.c_str(), "w");
2231  if (fd == nullptr)
2232  return false;
2233 
2234  fprintf(fd, "\
2235 #Viper650 - Position - Version 1.00\n\
2236 #\n\
2237 # R: A B C D E F\n\
2238 # Joint position in degrees\n\
2239 #\n\
2240 #\n\n");
2241 
2242  // Save positions in mm and deg
2243  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
2244  vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]));
2245 
2246  fclose(fd);
2247  return (true);
2248 }
2249 
2260 void vpRobotViper650::move(const std::string &filename)
2261 {
2262  vpColVector q;
2263 
2264  try {
2265  this->readPosFile(filename, q);
2267  this->setPositioningVelocity(10);
2269  }
2270  catch (...) {
2271  throw;
2272  }
2273 }
2274 
2294 {
2295  displacement.resize(6);
2296  displacement = 0;
2297 
2298  double q[6];
2299  vpColVector q_cur(6);
2300  double timestamp;
2301 
2302  InitTry;
2303 
2304  // Get the current joint position
2305  Try(PrimitiveACQ_POS_Viper650(q, &timestamp));
2306  for (unsigned int i = 0; i < njoint; i++) {
2307  q_cur[i] = q[i];
2308  }
2309 
2310  if (!m_first_time_getdis) {
2311  switch (frame) {
2312  case vpRobot::CAMERA_FRAME: {
2313  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2314  return;
2315  }
2316 
2317  case vpRobot::ARTICULAR_FRAME: {
2318  displacement = q_cur - m_q_prev_getdis;
2319  break;
2320  }
2321 
2322  case vpRobot::REFERENCE_FRAME: {
2323  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2324  return;
2325  }
2326 
2327  case vpRobot::MIXT_FRAME: {
2328  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2329  return;
2330  }
2332  std::cout << "getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2333  return;
2334  }
2335  }
2336  }
2337  else {
2338  m_first_time_getdis = false;
2339  }
2340 
2341  // Memorize the joint position for the next call
2342  m_q_prev_getdis = q_cur;
2343 
2344  CatchPrint();
2345  if (TryStt < 0) {
2346  vpERROR_TRACE("Cannot get velocity.");
2347  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
2348  }
2349 }
2350 
2365 {
2366  InitTry;
2367 
2368  Try(PrimitiveTFS_BIAS_Viper650());
2369 
2370  // Wait 500 ms to be sure the next measures take into account the bias
2371  vpTime::wait(500);
2372 
2373  CatchPrint();
2374  if (TryStt < 0) {
2375  vpERROR_TRACE("Cannot bias the force/torque sensor.");
2376  throw vpRobotException(vpRobotException::lowLevelError, "Cannot bias the force/torque sensor.");
2377  }
2378 }
2379 
2423 {
2424  InitTry;
2425 
2426  H.resize(6);
2427 
2428  Try(PrimitiveTFS_ACQ_Viper650(H.data));
2429 
2430  CatchPrint();
2431  if (TryStt < 0) {
2432  vpERROR_TRACE("Cannot get the force/torque measures.");
2433  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2434  }
2435 }
2436 
2478 {
2479  InitTry;
2480 
2481  vpColVector H(6);
2482 
2483  Try(PrimitiveTFS_ACQ_Viper650(H.data));
2484 
2485  return H;
2486 
2487  CatchPrint();
2488  if (TryStt < 0) {
2489  vpERROR_TRACE("Cannot get the force/torque measures.");
2490  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2491  }
2492  return H; // Here to avoid a warning, but should never be called
2493 }
2494 
2501 {
2502  InitTry;
2503  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
2504  std::cout << "Enable joint limits on axis 6..." << std::endl;
2505  CatchPrint();
2506  if (TryStt < 0) {
2507  vpERROR_TRACE("Cannot enable joint limits on axis 6");
2508  throw vpRobotException(vpRobotException::lowLevelError, "Cannot enable joint limits on axis 6.");
2509  }
2510 }
2511 
2523 {
2524  InitTry;
2525  Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1));
2526  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2527  CatchPrint();
2528  if (TryStt < 0) {
2529  vpERROR_TRACE("Cannot disable joint limits on axis 6");
2530  throw vpRobotException(vpRobotException::lowLevelError, "Cannot disable joint limits on axis 6.");
2531  }
2532 }
2533 
2543 {
2546 
2547  return;
2548 }
2549 
2570 {
2571  m_maxRotationVelocity_joint6 = w6_max;
2572  return;
2573 }
2574 
2582 double vpRobotViper650::getMaxRotationVelocityJoint6() const { return m_maxRotationVelocity_joint6; }
2583 
2591 {
2592  InitTry;
2593  Try(PrimitivePneumaticGripper_Viper650(1));
2594  std::cout << "Open the pneumatic gripper..." << std::endl;
2595  CatchPrint();
2596  if (TryStt < 0) {
2597  throw vpRobotException(vpRobotException::lowLevelError, "Cannot open the gripper.");
2598  }
2599 }
2600 
2609 {
2610  InitTry;
2611  Try(PrimitivePneumaticGripper_Viper650(0));
2612  std::cout << "Close the pneumatic gripper..." << std::endl;
2613  CatchPrint();
2614  if (TryStt < 0) {
2615  throw vpRobotException(vpRobotException::lowLevelError, "Cannot close the gripper.");
2616  }
2617 }
2618 END_VISP_NAMESPACE
2619 #elif !defined(VISP_BUILD_SHARED_LIBS)
2620 // Work around to avoid warning: libvisp_robot.a(vpRobotViper650.cpp.o) has
2621 // no symbols
2622 void dummy_vpRobotViper650() { };
2623 #endif
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:148
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpColVector & rad2deg()
Definition: vpColVector.h:1053
vpColVector & deg2rad()
Definition: vpColVector.h:380
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ functionNotImplementedError
Function not implemented.
Definition: vpException.h:66
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1661
static double rad(double deg)
Definition: vpMath.h:129
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
@ constructionError
Error from constructor.
@ positionOutOfRangeError
Position is out of range.
@ lowLevelError
Error thrown by the low level sdk.
void move(const std::string &filename)
void set_eMc(const vpHomogeneousMatrix &eMc_)
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
static const double m_defaultPositioningVelocity
virtual ~vpRobotViper650(void)
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void setPositioningVelocity(double velocity)
void enableJoint6Limits() const
void get_cVe(vpVelocityTwistMatrix &cVe) const
vpColVector getForceTorque() const
bool getPowerState() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocityJoint6(double w6_max)
void disableJoint6Limits() const
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
void biasForceTorqueSensor() const
void get_cMe(vpHomogeneousMatrix &cMe) const
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
@ AUTO
Automatic control mode (default).
@ ESTOP
Emergency stop activated.
double getMaxRotationVelocityJoint6() const
void setMaxRotationVelocity(double w_max)
double getTime() const
static bool readPosFile(const std::string &filename, vpColVector &q)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
double getPositioningVelocity(void) const
void closeGripper() const
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Class that defines a generic virtual robot.
Definition: vpRobot.h:59
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition: vpRobot.h:106
void setVerbose(bool verbose)
Definition: vpRobot.h:170
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:155
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164
vpControlFrameType
Definition: vpRobot.h:77
@ REFERENCE_FRAME
Definition: vpRobot.h:78
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ MIXT_FRAME
Definition: vpRobot.h:88
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:83
vpRobotStateType
Definition: vpRobot.h:65
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:274
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:110
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:252
double maxRotationVelocity
Definition: vpRobot.h:100
void setMaxRotationVelocity(double maxVr)
Definition: vpRobot.cpp:261
bool verbose_
Definition: vpRobot.h:118
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
vpRxyzVector & build(const vpRotationMatrix &R)
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRzyzVector.h:182
Implementation of a rotation vector as axis-angle minimal representation.
vpThetaUVector & build(const vpHomogeneousMatrix &M)
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
Modelization of the ADEPT Viper 650 robot.
Definition: vpViper650.h:95
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpViper650.h:168
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper650.h:129
void init(void)
Definition: vpViper650.cpp:133
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:120
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1229
vpTranslationVector etc
Definition: vpViper.h:158
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:153
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:921
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1158
vpColVector joint_max
Definition: vpViper.h:171
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:568
vpRxyzVector erc
Definition: vpViper.h:159
vpColVector joint_min
Definition: vpViper.h:172
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:969
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpViper.cpp:724
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:605
#define vpERROR_TRACE
Definition: vpDebug.h:409
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT void sleepMs(double t)