Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
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
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Interface for the Irisa's Viper S650 robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #include <visp3/core/vpConfig.h>
39 
40 #ifdef VISP_HAVE_VIPER650
41 
42 #include <signal.h>
43 #include <stdlib.h>
44 #include <sys/types.h>
45 #include <unistd.h>
46 
47 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpExponentialMap.h>
49 #include <visp3/core/vpDebug.h>
50 #include <visp3/core/vpVelocityTwistMatrix.h>
51 #include <visp3/core/vpThetaUVector.h>
52 #include <visp3/core/vpIoTools.h>
53 #include <visp3/robot/vpRobot.h>
54 #include <visp3/robot/vpRobotViper650.h>
55 
56 /* ---------------------------------------------------------------------- */
57 /* --- STATIC ----------------------------------------------------------- */
58 /* ---------------------------------------------------------------------- */
59 
60 bool vpRobotViper650::robotAlreadyCreated = false;
61 
70 
71 /* ---------------------------------------------------------------------- */
72 /* --- EMERGENCY STOP --------------------------------------------------- */
73 /* ---------------------------------------------------------------------- */
74 
82 void emergencyStopViper650(int signo)
83 {
84  std::cout << "Stop the Viper650 application by signal ("
85  << signo << "): " << (char)7 ;
86  switch(signo)
87  {
88  case SIGINT:
89  std::cout << "SIGINT (stop by ^C) " << std::endl ; break ;
90  case SIGBUS:
91  std::cout <<"SIGBUS (stop due to a bus error) " << std::endl ; break ;
92  case SIGSEGV:
93  std::cout <<"SIGSEGV (stop due to a segmentation fault) " << std::endl ; break ;
94  case SIGKILL:
95  std::cout <<"SIGKILL (stop by CTRL \\) " << std::endl ; break ;
96  case SIGQUIT:
97  std::cout <<"SIGQUIT " << std::endl ; break ;
98  default :
99  std::cout << signo << std::endl ;
100 }
101  //std::cout << "Emergency stop called\n";
102  // PrimitiveESTOP_Viper650();
103  PrimitiveSTOP_Viper650();
104  std::cout << "Robot was stopped\n";
105 
106  // Free allocated resources
107  // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
108 
109  fprintf(stdout, "Application ");
110  fflush(stdout);
111  kill(getpid(), SIGKILL);
112  exit(1) ;
113 }
114 
115 /* ---------------------------------------------------------------------- */
116 /* --- CONSTRUCTOR ------------------------------------------------------ */
117 /* ---------------------------------------------------------------------- */
118 
174 vpRobotViper650::vpRobotViper650 (bool verbose)
175  :
176  vpViper650 (),
177  vpRobot ()
178 {
179 
180  /*
181  #define SIGHUP 1 // hangup
182  #define SIGINT 2 // interrupt (rubout)
183  #define SIGQUIT 3 // quit (ASCII FS)
184  #define SIGILL 4 // illegal instruction (not reset when caught)
185  #define SIGTRAP 5 // trace trap (not reset when caught)
186  #define SIGIOT 6 // IOT instruction
187  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
188  #define SIGEMT 7 // EMT instruction
189  #define SIGFPE 8 // floating point exception
190  #define SIGKILL 9 // kill (cannot be caught or ignored)
191  #define SIGBUS 10 // bus error
192  #define SIGSEGV 11 // segmentation violation
193  #define SIGSYS 12 // bad argument to system call
194  #define SIGPIPE 13 // write on a pipe with no one to read it
195  #define SIGALRM 14 // alarm clock
196  #define SIGTERM 15 // software termination signal from kill
197  */
198 
199  signal(SIGINT, emergencyStopViper650);
200  signal(SIGBUS, emergencyStopViper650) ;
201  signal(SIGSEGV, emergencyStopViper650) ;
202  signal(SIGKILL, emergencyStopViper650);
203  signal(SIGQUIT, emergencyStopViper650);
204 
205  setVerbose(verbose);
206  if (verbose_)
207  std::cout << "Open communication with MotionBlox.\n";
208  try {
209  this->init();
211  }
212  catch(...) {
213  // vpERROR_TRACE("Error caught") ;
214  throw ;
215  }
216  positioningVelocity = defaultPositioningVelocity ;
217 
218  maxRotationVelocity_joint6 = maxRotationVelocity;
219 
220  vpRobotViper650::robotAlreadyCreated = true;
221 
222  return ;
223 }
224 
225 
226 /* ------------------------------------------------------------------------ */
227 /* --- INITIALISATION ----------------------------------------------------- */
228 /* ------------------------------------------------------------------------ */
229 
251 void
253 {
254  InitTry;
255 
256  // Initialise private variables used to compute the measured velocities
257  q_prev_getvel.resize(6);
258  q_prev_getvel = 0;
259  time_prev_getvel = 0;
260  first_time_getvel = true;
261 
262  // Initialise private variables used to compute the measured displacement
263  q_prev_getdis.resize(6);
264  q_prev_getdis = 0;
265  first_time_getdis = true;
266 
267  // Initialize the firewire connection
268  Try( InitializeConnection(verbose_) );
269 
270  // Connect to the servoboard using the servo board GUID
271  Try( InitializeNode_Viper650() );
272 
273  Try( PrimitiveRESET_Viper650() );
274 
275  // Enable the joint limits on axis 6
276  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
277 
278  // Update the eMc matrix in the low level controller
280 
281  // Look if the power is on or off
282  UInt32 HIPowerStatus;
283  UInt32 EStopStatus;
284  Try( PrimitiveSTATUS_Viper650(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
285  &HIPowerStatus));
286  CAL_Wait(0.1);
287 
288  // Print the robot status
289  if (verbose_) {
290  std::cout << "Robot status: ";
291  switch(EStopStatus) {
292  case ESTOP_AUTO:
293  controlMode = AUTO;
294  if (HIPowerStatus == 0)
295  std::cout << "Power is OFF" << std::endl;
296  else
297  std::cout << "Power is ON" << std::endl;
298  break;
299 
300  case ESTOP_MANUAL:
301  controlMode = MANUAL;
302  if (HIPowerStatus == 0)
303  std::cout << "Power is OFF" << std::endl;
304  else
305  std::cout << "Power is ON" << std::endl;
306  break;
307  case ESTOP_ACTIVATED:
308  controlMode = ESTOP;
309  std::cout << "Emergency stop is activated" << std::endl;
310  break;
311  default:
312  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
313  std::cout << "You have to call Adept for maintenance..." << std::endl;
314  // Free allocated resources
315  }
316  std::cout << std::endl;
317  }
318  // get real joint min/max from the MotionBlox
319  Try( PrimitiveJOINT_MINMAX_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], joint_max[i]);
326  // }
327 
328  // If an error occur in the low level controller, goto here
329  //CatchPrint();
330  Catch();
331 
332  // Test if an error occurs
333  if (TryStt == -20001)
334  printf("No connection detected. Check if the robot is powered on \n"
335  "and if the firewire link exist between the MotionBlox and this computer.\n");
336  else if (TryStt == -675)
337  printf(" Timeout enabling power...\n");
338 
339  if (TryStt < 0) {
340  // Power off the robot
341  PrimitivePOWEROFF_Viper650();
342  // Free allocated resources
343  ShutDownConnection();
344 
345  std::cout << "Cannot open connection with the motionblox..." << std::endl;
347  "Cannot open connection with the motionblox");
348  }
349  return ;
350 }
351 
410 void
413 {
414  // Read the robot constants from files
415  // - joint [min,max], coupl_56, long_56
416  // - camera extrinsic parameters relative to eMc
417  vpViper650::init(tool, projModel);
418 
419  InitTry;
420 
421  // Get real joint min/max from the MotionBlox
422  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
423  // Convert units from degrees to radians
424  joint_min.deg2rad();
425  joint_max.deg2rad();
426 
427  // for (unsigned int i=0; i < njoint; i++) {
428  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
429  // }
430 
431  // Set the camera constant (eMc pose) in the MotionBlox
432  double eMc_pose[6];
433  for (unsigned int i=0; i < 3; i ++) {
434  eMc_pose[i] = etc[i]; // translation in meters
435  eMc_pose[i+3] = erc[i]; // rotation in rad
436  }
437  // Update the eMc pose in the low level controller
438  Try( PrimitiveCONST_Viper650(eMc_pose) );
439 
440  CatchPrint();
441  return ;
442 }
443 
494 void
495 vpRobotViper650::init (vpViper650::vpToolType tool, const std::string &filename)
496 {
497  vpViper650::init(tool, filename);
498 
499  InitTry;
500 
501  // Get real joint min/max from the MotionBlox
502  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
503  // Convert units from degrees to radians
504  joint_min.deg2rad();
505  joint_max.deg2rad();
506 
507  // for (unsigned int i=0; i < njoint; i++) {
508  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
509  // }
510 
511  // Set the camera constant (eMc pose) in the MotionBlox
512  double eMc_pose[6];
513  for (unsigned int i=0; i < 3; i ++) {
514  eMc_pose[i] = etc[i]; // translation in meters
515  eMc_pose[i+3] = erc[i]; // rotation in rad
516  }
517  // Update the eMc pose in the low level controller
518  Try( PrimitiveCONST_Viper650(eMc_pose) );
519 
520  CatchPrint();
521  return ;
522 }
523 
560 void
562 {
563  vpViper650::init(tool, eMc_);
564 
565  InitTry;
566 
567  // Get real joint min/max from the MotionBlox
568  Try( PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data) );
569  // Convert units from degrees to radians
570  joint_min.deg2rad();
571  joint_max.deg2rad();
572 
573  // for (unsigned int i=0; i < njoint; i++) {
574  // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i], joint_max[i]);
575  // }
576 
577  // Set the camera constant (eMc pose) in the MotionBlox
578  double eMc_pose[6];
579  for (unsigned int i=0; i < 3; i ++) {
580  eMc_pose[i] = etc[i]; // translation in meters
581  eMc_pose[i+3] = erc[i]; // rotation in rad
582  }
583  // Update the eMc pose in the low level controller
584  Try( PrimitiveCONST_Viper650(eMc_pose) );
585 
586  CatchPrint();
587  return ;
588 }
589 
601 void
603 {
604  this->vpViper650::set_eMc(eMc_);
605 
606  InitTry;
607 
608  // Set the camera constant (eMc pose) in the MotionBlox
609  double eMc_pose[6];
610  for (unsigned int i=0; i < 3; i ++) {
611  eMc_pose[i] = etc[i]; // translation in meters
612  eMc_pose[i+3] = erc[i]; // rotation in rad
613  }
614  // Update the eMc pose in the low level controller
615  Try( PrimitiveCONST_Viper650(eMc_pose) );
616 
617  CatchPrint();
618 
619  return ;
620 }
621 
634 void
636 {
637  this->vpViper650::set_eMc(etc_,erc_);
638 
639  InitTry;
640 
641  // Set the camera constant (eMc pose) in the MotionBlox
642  double eMc_pose[6];
643  for (unsigned int i=0; i < 3; i ++) {
644  eMc_pose[i] = etc[i]; // translation in meters
645  eMc_pose[i+3] = erc[i]; // rotation in rad
646  }
647  // Update the eMc pose in the low level controller
648  Try( PrimitiveCONST_Viper650(eMc_pose) );
649 
650  CatchPrint();
651 
652  return ;
653 }
654 
655 /* ------------------------------------------------------------------------ */
656 /* --- DESTRUCTOR --------------------------------------------------------- */
657 /* ------------------------------------------------------------------------ */
658 
666 {
667  InitTry;
668 
670 
671  // Look if the power is on or off
672  UInt32 HIPowerStatus;
673  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
674  &HIPowerStatus));
675  CAL_Wait(0.1);
676 
677  // if (HIPowerStatus == 1) {
678  // fprintf(stdout, "Power OFF the robot\n");
679  // fflush(stdout);
680 
681  // Try( PrimitivePOWEROFF_Viper650() );
682  // }
683 
684  // Free allocated resources
685  ShutDownConnection();
686 
687  vpRobotViper650::robotAlreadyCreated = false;
688 
689  CatchPrint();
690  return;
691 }
692 
693 
694 
695 
704 {
705  InitTry;
706 
707  switch (newState) {
708  case vpRobot::STATE_STOP: {
709  // Start primitive STOP only if the current state is Velocity
711  Try( PrimitiveSTOP_Viper650() );
712  vpTime::sleepMs(100); // needed to ensure velocity task ends up on low level
713  }
714  break;
715  }
718  std::cout << "Change the control mode from velocity to position control.\n";
719  Try( PrimitiveSTOP_Viper650() );
720  }
721  else {
722  //std::cout << "Change the control mode from stop to position control.\n";
723  }
724  this->powerOn();
725  break;
726  }
729  std::cout << "Change the control mode from stop to velocity control.\n";
730  }
731  this->powerOn();
732  break;
733  }
734  default:
735  break ;
736  }
737 
738  CatchPrint();
739 
740  return vpRobot::setRobotState (newState);
741 }
742 
743 
744 /* ------------------------------------------------------------------------ */
745 /* --- STOP --------------------------------------------------------------- */
746 /* ------------------------------------------------------------------------ */
747 
755 void
757 {
759  return;
760 
761  InitTry;
762  Try( PrimitiveSTOP_Viper650() );
764 
765  CatchPrint();
766  if (TryStt < 0) {
767  vpERROR_TRACE ("Cannot stop robot motion");
769  "Cannot stop robot motion.");
770  }
771 }
772 
782 void
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(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
795  &HIPowerStatus));
796  if (EStopStatus == ESTOP_AUTO) {
797  controlMode = AUTO;
798  break; // exit for loop
799  }
800  else if (EStopStatus == ESTOP_MANUAL) {
801  controlMode = MANUAL;
802  break; // exit for loop
803  }
804  else if (EStopStatus == ESTOP_ACTIVATED) {
805  controlMode = ESTOP;
806  if (firsttime) {
807  std::cout << "Emergency stop is activated! \n"
808  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
809  firsttime = false;
810  }
811  fprintf(stdout, "Remaining time %us \r", nitermax-i);
812  fflush(stdout);
813  CAL_Wait(1);
814  }
815  else {
816  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
817  std::cout << "You have to call Adept for maintenance..." << std::endl;
818  // Free allocated resources
819  ShutDownConnection();
820  exit(0);
821  }
822  }
823 
824  if (EStopStatus == ESTOP_ACTIVATED)
825  std::cout << std::endl;
826 
827  if (EStopStatus == ESTOP_ACTIVATED) {
828  std::cout << "Sorry, cannot power on the robot." << std::endl;
830  "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");
844  "Cannot power off the robot.");
845  }
846 }
847 
857 void
859 {
860  InitTry;
861 
862  // Look if the power is on or off
863  UInt32 HIPowerStatus;
864  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
865  &HIPowerStatus));
866  CAL_Wait(0.1);
867 
868  if (HIPowerStatus == 1) {
869  fprintf(stdout, "Power OFF the Viper650 robot\n");
870  fflush(stdout);
871 
872  Try( PrimitivePOWEROFF_Viper650() );
873  }
874 
875  CatchPrint();
876  if (TryStt < 0) {
877  vpERROR_TRACE ("Cannot power off the robot");
879  "Cannot power off the robot.");
880  }
881 }
882 
894 bool
896 {
897  InitTry;
898  bool status = false;
899  // Look if the power is on or off
900  UInt32 HIPowerStatus;
901  Try( PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, NULL,
902  &HIPowerStatus));
903  CAL_Wait(0.1);
904 
905  if (HIPowerStatus == 1) {
906  status = true;
907  }
908 
909  CatchPrint();
910  if (TryStt < 0) {
911  vpERROR_TRACE ("Cannot get the power status");
913  "Cannot get the power status.");
914  }
915  return status;
916 }
917 
927 void
929 {
930  vpHomogeneousMatrix cMe ;
931  vpViper650::get_cMe(cMe) ;
932 
933  cVe.buildFrom(cMe) ;
934 }
935 
947 void
949 {
950  vpViper650::get_cMe(cMe) ;
951 }
952 
953 
965 void
967 {
968 
969  double position[6];
970  double timestamp;
971 
972  InitTry;
973  Try( PrimitiveACQ_POS_J_Viper650(position, &timestamp) );
974  CatchPrint();
975 
976  vpColVector q(6);
977  for (unsigned int i=0; i < njoint; i++)
978  q[i] = vpMath::rad(position[i]);
979 
980  try
981  {
982  vpViper650::get_eJe(q, eJe) ;
983  }
984  catch(...)
985  {
986  vpERROR_TRACE("catch exception ") ;
987  throw ;
988  }
989 }
1002 void
1004 {
1005 
1006  double position[6];
1007  double timestamp;
1008 
1009  InitTry;
1010  Try( PrimitiveACQ_POS_Viper650(position, &timestamp) );
1011  CatchPrint();
1012 
1013  vpColVector q(6);
1014  for (unsigned int i=0; i < njoint; i++)
1015  q[i] = position[i];
1016 
1017  try
1018  {
1019  vpViper650::get_fJe(q, fJe) ;
1020  }
1021  catch(...)
1022  {
1023  vpERROR_TRACE("Error caught");
1024  throw ;
1025  }
1026 }
1027 
1065 void
1067 {
1068  positioningVelocity = velocity;
1069 }
1070 
1076 double
1078 {
1079  return positioningVelocity;
1080 }
1081 
1082 
1160 void
1162  const vpColVector & position )
1163 {
1164 
1166  {
1167  vpERROR_TRACE ("Robot was not in position-based control\n"
1168  "Modification of the robot state");
1170  }
1171 
1172  vpColVector destination(njoint);
1173  int error = 0;
1174  double timestamp;
1175 
1176  InitTry;
1177  switch(frame) {
1178  case vpRobot::CAMERA_FRAME : {
1179  vpColVector q(njoint);
1180  Try( PrimitiveACQ_POS_Viper650(q.data, &timestamp) );
1181 
1182  // Convert degrees into rad
1183  q.deg2rad();
1184 
1185  // Get fMc from the inverse kinematics
1186  vpHomogeneousMatrix fMc;
1187  vpViper650::get_fMc(q, fMc);
1188 
1189  // Set cMc from the input position
1190  vpTranslationVector txyz;
1191  vpRxyzVector rxyz;
1192  for (unsigned int i=0; i < 3; i++) {
1193  txyz[i] = position[i];
1194  rxyz[i] = position[i+3];
1195  }
1196 
1197  // Compute cMc2
1198  vpRotationMatrix cRc2(rxyz);
1199  vpHomogeneousMatrix cMc2(txyz, cRc2);
1200 
1201  // Compute the new position to reach: fMc*cMc2
1202  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1203 
1204  // Compute the corresponding joint position from the inverse kinematics
1205  unsigned int solution = this->getInverseKinematics(fMc2, q);
1206  if (solution) { // Position is reachable
1207  destination = q;
1208  // convert rad to deg requested for the low level controller
1209  destination.rad2deg();
1210  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
1211  Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1212  }
1213  else {
1214  // Cartesian position is out of range
1215  error = -1;
1216  }
1217 
1218  break ;
1219  }
1220  case vpRobot::ARTICULAR_FRAME: {
1221  destination = position;
1222  // convert rad to deg requested for the low level controller
1223  destination.rad2deg();
1224 
1225  //std::cout << "Joint destination (deg): " << destination.t() << std::endl;
1226  Try( PrimitiveMOVE_J_Viper650(destination.data, positioningVelocity) );
1227  Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1228  break ;
1229 
1230  }
1231  case vpRobot::REFERENCE_FRAME: {
1232  // Convert angles from Rxyz representation to Rzyz representation
1233  vpRxyzVector rxyz(position[3],position[4],position[5]);
1234  vpRotationMatrix R(rxyz);
1235  vpRzyzVector rzyz(R);
1236 
1237  for (unsigned int i=0; i <3; i++) {
1238  destination[i] = position[i];
1239  destination[i+3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1240  }
1241  int configuration = 0; // keep the actual configuration
1242 
1243  //std::cout << "Base frame destination Rzyz (deg): " << destination.t() << std::endl;
1244  Try( PrimitiveMOVE_C_Viper650(destination.data, configuration,
1245  positioningVelocity) );
1246  Try( WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000) );
1247 
1248  break ;
1249  }
1250  case vpRobot::MIXT_FRAME:
1251  {
1252  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1254  "Positionning error: "
1255  "Mixt frame not implemented.");
1256  }
1257  }
1258 
1259  CatchPrint();
1260  if (TryStt == InvalidPosition || TryStt == -1023)
1261  std::cout << " : Position out of range.\n";
1262 
1263  else if (TryStt == -3019) {
1264  if (frame == vpRobot::ARTICULAR_FRAME)
1265  std::cout << " : Joint position out of range.\n";
1266  else
1267  std::cout << " : Cartesian position leads to a joint position out of range.\n";
1268  }
1269  else if (TryStt < 0)
1270  std::cout << " : Unknown error (see Fabien).\n";
1271  else if (error == -1)
1272  std::cout << "Position out of range.\n";
1273 
1274  if (TryStt < 0 || error < 0) {
1275  vpERROR_TRACE ("Positionning error.");
1277  "Position out of range.");
1278  }
1279 
1280  return ;
1281 }
1282 
1349  const double pos1,
1350  const double pos2,
1351  const double pos3,
1352  const double pos4,
1353  const double pos5,
1354  const double pos6)
1355 {
1356  try{
1357  vpColVector position(6) ;
1358  position[0] = pos1 ;
1359  position[1] = pos2 ;
1360  position[2] = pos3 ;
1361  position[3] = pos4 ;
1362  position[4] = pos5 ;
1363  position[5] = pos6 ;
1364 
1365  setPosition(frame, position) ;
1366  }
1367  catch(...)
1368  {
1369  vpERROR_TRACE("Error caught");
1370  throw ;
1371  }
1372 }
1373 
1413 void vpRobotViper650::setPosition(const std::string &filename)
1414 {
1415  vpColVector q;
1416  bool ret;
1417 
1418  ret = this->readPosFile(filename, q);
1419 
1420  if (ret == false) {
1421  vpERROR_TRACE ("Bad position in \"%s\"", filename.c_str());
1423  "Bad position in filename.");
1424  }
1427 }
1428 
1498  vpColVector &position,
1499  double &timestamp)
1500 {
1501 
1502  InitTry;
1503 
1504  position.resize (6);
1505 
1506  switch (frame) {
1507  case vpRobot::CAMERA_FRAME : {
1508  position = 0;
1509  return;
1510  }
1511  case vpRobot::ARTICULAR_FRAME : {
1512  Try( PrimitiveACQ_POS_J_Viper650(position.data, &timestamp) );
1513  //vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1514  position.deg2rad();
1515 
1516  return;
1517  }
1518  case vpRobot::REFERENCE_FRAME : {
1519  Try( PrimitiveACQ_POS_C_Viper650(position.data, &timestamp) );
1520  // vpCTRACE << "Get cartesian position " << position.t() << std::endl;
1521  // 1=tx, 2=ty, 3=tz in meters; 4=Rz 5=Ry 6=Rz in deg
1522  // Convert Euler Rzyz angles from deg to rad
1523  for (unsigned int i=3; i <6; i++)
1524  position[i] = vpMath::rad(position[i]);
1525  // Convert Rzyz angles into Rxyz representation
1526  vpRzyzVector rzyz(position[3], position[4], position[5]);
1527  vpRotationMatrix R(rzyz);
1528  vpRxyzVector rxyz(R);
1529 
1530  // Update the position using Rxyz representation
1531  for (unsigned int i=0; i <3; i++)
1532  position[i+3] = rxyz[i];
1533  // vpCTRACE << "Cartesian position Rxyz (deg)"
1534  // << position[0] << " " << position[1] << " " << position[2] << " "
1535  // << vpMath::deg(position[3]) << " "
1536  // << vpMath::deg(position[4]) << " "
1537  // << vpMath::deg(position[5]) << std::endl;
1538 
1539  break ;
1540  }
1541  case vpRobot::MIXT_FRAME: {
1542  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1544  "Cannot get position in mixt frame: "
1545  "not implemented");
1546  }
1547  }
1548 
1549  CatchPrint();
1550  if (TryStt < 0) {
1551  vpERROR_TRACE ("Cannot get position.");
1553  "Cannot get position.");
1554  }
1555 
1556  return;
1557 }
1558 
1569  vpColVector &position)
1570 {
1571  double timestamp;
1572  getPosition(frame, position, timestamp);
1573 }
1574 
1587  vpPoseVector &position,
1588  double &timestamp)
1589 {
1590  vpColVector posRxyz;
1591  //recupere position en Rxyz
1592  this->getPosition(frame, posRxyz, timestamp);
1593  vpRxyzVector RxyzVect;
1594  for (unsigned int j=0;j<3;j++)
1595  RxyzVect[j]=posRxyz[j+3];
1596  //recupere le vecteur thetaU correspondant
1597  vpThetaUVector RtuVect(RxyzVect);
1598 
1599  //remplit le vpPoseVector avec translation et rotation ThetaU
1600  for (unsigned int j=0;j<3;j++)
1601  {
1602  position[j]=posRxyz[j];
1603  position[j+3]=RtuVect[j];
1604  }
1605 }
1606 
1617  vpPoseVector &position)
1618 {
1619  double timestamp;
1620  getPosition(frame, position, timestamp);
1621 }
1622 
1627 {
1628  double timestamp;
1629  PrimitiveACQ_TIME_Viper650(&timestamp);
1630  return timestamp;
1631 }
1632 
1705 void
1707  const vpColVector & vel)
1708 {
1710  vpERROR_TRACE ("Cannot send a velocity to the robot "
1711  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1713  "Cannot send a velocity to the robot "
1714  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1715  }
1716 
1717  vpColVector vel_sat(6);
1718 
1719  // Velocity saturation
1720  switch(frame) {
1721  // saturation in cartesian space
1722  case vpRobot::CAMERA_FRAME :
1724  case vpRobot::MIXT_FRAME : {
1725  vpColVector vel_max(6);
1726 
1727  for (unsigned int i=0; i<3; i++)
1728  vel_max[i] = getMaxTranslationVelocity();
1729  for (unsigned int i=3; i<6; i++)
1730  vel_max[i] = getMaxRotationVelocity();
1731 
1732  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1733 
1734  break;
1735  }
1736  // saturation in joint space
1737  case vpRobot::ARTICULAR_FRAME : {
1738  vpColVector vel_max(6);
1739 
1740  //if (getMaxRotationVelocity() == getMaxRotationVelocityJoint6()) {
1741  if (std::fabs(getMaxRotationVelocity() - getMaxRotationVelocityJoint6()) < std::numeric_limits<double>::epsilon()) {
1742  for (unsigned int i=0; i<6; i++)
1743  vel_max[i] = getMaxRotationVelocity();
1744  }
1745  else {
1746  for (unsigned int i=0; i<5; i++)
1747  vel_max[i] = getMaxRotationVelocity();
1748  vel_max[5] = getMaxRotationVelocityJoint6();
1749  }
1750 
1751  vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1752 
1753  }
1754  }
1755 
1756  InitTry;
1757 
1758  switch(frame) {
1759  case vpRobot::CAMERA_FRAME : {
1760  // Send velocities in m/s and rad/s
1761  // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1762  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPCAM_VIPER650) );
1763  break ;
1764  }
1765  case vpRobot::ARTICULAR_FRAME : {
1766  // Convert all the velocities from rad/s into deg/s
1767  vel_sat.rad2deg();
1768  //std::cout << "Vitesse appliquee: " << vel_sat.t();
1769  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER650) );
1770  Try( PrimitiveMOVESPEED_Viper650(vel_sat.data) );
1771  break ;
1772  }
1773  case vpRobot::REFERENCE_FRAME : {
1774  // Send velocities in m/s and rad/s
1775  std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1776  Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPFIX_VIPER650) );
1777  break ;
1778  }
1779  case vpRobot::MIXT_FRAME : {
1780  //Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPMIX_VIPER650) );
1781  break ;
1782  }
1783  default: {
1784  vpERROR_TRACE ("Error in spec of vpRobot. "
1785  "Case not taken in account.");
1786  return;
1787  }
1788  }
1789 
1790  Catch();
1791  if (TryStt < 0) {
1792  if (TryStt == VelStopOnJoint) {
1793  UInt32 axisInJoint[njoint];
1794  PrimitiveSTATUS_Viper650(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1795  for (unsigned int i=0; i < njoint; i ++) {
1796  if (axisInJoint[i])
1797  std::cout << "\nWarning: Velocity control stopped: axis "
1798  << i+1 << " on joint limit!" <<std::endl;
1799  }
1800  }
1801  else {
1802  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1803  if (TryString != NULL) {
1804  // The statement is in TryString, but we need to check the validity
1805  printf(" Error sentence %s\n", TryString); // Print the TryString
1806  }
1807  else {
1808  printf("\n");
1809  }
1810  }
1811  }
1812 
1813  return;
1814 }
1815 
1816 
1817 
1818 
1819 
1820 
1821 /* ------------------------------------------------------------------------ */
1822 /* --- GET ---------------------------------------------------------------- */
1823 /* ------------------------------------------------------------------------ */
1824 
1825 
1883  vpColVector & velocity, double &timestamp)
1884 {
1885  velocity.resize (6);
1886  velocity = 0;
1887 
1888  vpColVector q_cur(6);
1889  vpHomogeneousMatrix fMc_cur;
1890  vpHomogeneousMatrix cMc; // camera displacement
1891  double time_cur;
1892 
1893  InitTry;
1894 
1895  // Get the current joint position
1896  Try( PrimitiveACQ_POS_J_Viper650(q_cur.data, &timestamp) );
1897  time_cur = timestamp;
1898  q_cur.deg2rad();
1899 
1900  // Get the camera pose from the direct kinematics
1901  vpViper650::get_fMc(q_cur, fMc_cur);
1902 
1903  if ( ! first_time_getvel ) {
1904 
1905  switch (frame) {
1906  case vpRobot::CAMERA_FRAME: {
1907  // Compute the displacement of the camera since the previous call
1908  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1909 
1910  // Compute the velocity of the camera from this displacement
1911  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1912 
1913  break ;
1914  }
1915 
1916  case vpRobot::ARTICULAR_FRAME: {
1917  velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1918  break ;
1919  }
1920 
1921  case vpRobot::REFERENCE_FRAME: {
1922  // Compute the displacement of the camera since the previous call
1923  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1924 
1925  // Compute the velocity of the camera from this displacement
1926  vpColVector v;
1927  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1928 
1929  // Express this velocity in the reference frame
1930  vpVelocityTwistMatrix fVc(fMc_cur);
1931  velocity = fVc * v;
1932 
1933  break ;
1934  }
1935 
1936  case vpRobot::MIXT_FRAME: {
1937  // Compute the displacement of the camera since the previous call
1938  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1939 
1940  // Compute the ThetaU representation for the rotation
1941  vpRotationMatrix cRc;
1942  cMc.extract(cRc);
1943  vpThetaUVector thetaU;
1944  thetaU.buildFrom(cRc);
1945 
1946  for (unsigned int i=0; i < 3; i++) {
1947  // Compute the translation displacement in the reference frame
1948  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1949  // Update the rotation displacement in the camera frame
1950  velocity[i+3] = thetaU[i];
1951  }
1952 
1953  // Compute the velocity
1954  velocity /= (time_cur - time_prev_getvel);
1955  break ;
1956  }
1957  }
1958  }
1959  else {
1960  first_time_getvel = false;
1961  }
1962 
1963  // Memorize the camera pose for the next call
1964  fMc_prev_getvel = fMc_cur;
1965 
1966  // Memorize the joint position for the next call
1967  q_prev_getvel = q_cur;
1968 
1969  // Memorize the time associated to the joint position for the next call
1970  time_prev_getvel = time_cur;
1971 
1972 
1973  CatchPrint();
1974  if (TryStt < 0) {
1975  vpERROR_TRACE ("Cannot get velocity.");
1977  "Cannot get velocity.");
1978  }
1979 }
1980 
1990  vpColVector & velocity)
1991 {
1992  double timestamp;
1993  getVelocity(frame, velocity, timestamp);
1994 }
1995 
2047 {
2048  vpColVector velocity;
2049  getVelocity (frame, velocity, timestamp);
2050 
2051  return velocity;
2052 }
2053 
2063 {
2064  vpColVector velocity;
2065  double timestamp;
2066  getVelocity (frame, velocity, timestamp);
2067 
2068  return velocity;
2069 }
2070 
2136 bool vpRobotViper650::readPosFile(const std::string &filename, vpColVector &q)
2137 {
2138  std::ifstream fd(filename.c_str(), std::ios::in);
2139 
2140  if(! fd.is_open()) {
2141  return false;
2142  }
2143 
2144  std::string line;
2145  std::string key("R:");
2146  std::string id("#Viper650 - Position");
2147  bool pos_found = false;
2148  int lineNum = 0;
2149 
2150  q.resize(njoint);
2151 
2152  while(std::getline(fd, line)) {
2153  lineNum ++;
2154  if (lineNum == 1) {
2155  if(! (line.compare(0, id.size(), id) == 0)) { // check if Viper650 position file
2156  std::cout << "Error: this position file " << filename << " is not for Viper650 robot" << std::endl;
2157  return false;
2158  }
2159  }
2160  if((line.compare(0, 1, "#") == 0)) { // skip comment
2161  continue;
2162  }
2163  if((line.compare(0, key.size(), key) == 0)) { // decode position
2164  // check if there are at least njoint values in the line
2165  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2166  if (chain.size() < njoint+1) // try to split with tab separator
2167  chain = vpIoTools::splitChain(line, std::string("\t"));
2168  if(chain.size() < njoint+1)
2169  continue;
2170 
2171  std::istringstream ss(line);
2172  std::string key_;
2173  ss >> key_;
2174  for (unsigned int i=0; i< njoint; i++)
2175  ss >> q[i];
2176  pos_found = true;
2177  break;
2178  }
2179  }
2180 
2181  // converts rotations from degrees into radians
2182  q.deg2rad();
2183 
2184  fd.close();
2185 
2186  if (!pos_found) {
2187  std::cout << "Error: unable to find a position for Viper650 robot in " << filename << std::endl;
2188  return false;
2189  }
2190 
2191  return true;
2192 }
2193 
2217 bool
2218  vpRobotViper650::savePosFile(const std::string &filename, const vpColVector &q)
2219 {
2220 
2221  FILE * fd ;
2222  fd = fopen(filename.c_str(), "w") ;
2223  if (fd == NULL)
2224  return false;
2225 
2226  fprintf(fd, "\
2227 #Viper650 - Position - Version 1.00\n\
2228 #\n\
2229 # R: A B C D E F\n\
2230 # Joint position in degrees\n\
2231 #\n\
2232 #\n\n");
2233 
2234  // Save positions in mm and deg
2235  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2236  vpMath::deg(q[0]),
2237  vpMath::deg(q[1]),
2238  vpMath::deg(q[2]),
2239  vpMath::deg(q[3]),
2240  vpMath::deg(q[4]),
2241  vpMath::deg(q[5]));
2242 
2243  fclose(fd) ;
2244  return (true);
2245 }
2246 
2257 void
2258 vpRobotViper650::move(const std::string &filename)
2259 {
2260  vpColVector q;
2261 
2262  try {
2263  this->readPosFile(filename, q) ;
2265  this->setPositioningVelocity(10);
2267  }
2268  catch(...) {
2269  throw;
2270  }
2271 }
2272 
2286 void
2287  vpRobotViper650::getCameraDisplacement(vpColVector &displacement)
2288 {
2289  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2290 }
2302 void
2303  vpRobotViper650::getArticularDisplacement(vpColVector &displacement)
2304 {
2306 }
2307 
2328 void
2330  vpColVector &displacement)
2331 {
2332  displacement.resize (6);
2333  displacement = 0;
2334 
2335  double q[6];
2336  vpColVector q_cur(6);
2337  double timestamp;
2338 
2339  InitTry;
2340 
2341  // Get the current joint position
2342  Try( PrimitiveACQ_POS_Viper650(q, &timestamp) );
2343  for (unsigned int i=0; i < njoint; i ++) {
2344  q_cur[i] = q[i];
2345  }
2346 
2347  if ( ! first_time_getdis ) {
2348  switch (frame) {
2349  case vpRobot::CAMERA_FRAME: {
2350  std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2351  return;
2352  }
2353 
2354  case vpRobot::ARTICULAR_FRAME: {
2355  displacement = q_cur - q_prev_getdis;
2356  break ;
2357  }
2358 
2359  case vpRobot::REFERENCE_FRAME: {
2360  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2361  return;
2362  }
2363 
2364  case vpRobot::MIXT_FRAME: {
2365  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2366  return;
2367  }
2368  }
2369  }
2370  else {
2371  first_time_getdis = false;
2372  }
2373 
2374  // Memorize the joint position for the next call
2375  q_prev_getdis = q_cur;
2376 
2377  CatchPrint();
2378  if (TryStt < 0) {
2379  vpERROR_TRACE ("Cannot get velocity.");
2381  "Cannot get velocity.");
2382  }
2383 }
2384 
2398 void
2400 {
2401  InitTry;
2402 
2403  Try( PrimitiveTFS_BIAS_Viper650() );
2404 
2405  // Wait 500 ms to be sure the next measures take into account the bias
2406  vpTime::wait(500);
2407 
2408  CatchPrint();
2409  if (TryStt < 0) {
2410  vpERROR_TRACE ("Cannot bias the force/torque sensor.");
2412  "Cannot bias the force/torque sensor.");
2413  }
2414 }
2415 
2456 {
2457  InitTry;
2458 
2459  H.resize (6);
2460 
2461  Try( PrimitiveTFS_ACQ_Viper650(H.data) );
2462 
2463  CatchPrint();
2464  if (TryStt < 0) {
2465  vpERROR_TRACE ("Cannot get the force/torque measures.");
2467  "Cannot get force/torque measures.");
2468  }
2469 }
2470 
2509 {
2510  InitTry;
2511 
2512  vpColVector H(6);
2513 
2514  Try( PrimitiveTFS_ACQ_Viper650(H.data) );
2515 
2516  return H;
2517 
2518  CatchPrint();
2519  if (TryStt < 0) {
2520  vpERROR_TRACE ("Cannot get the force/torque measures.");
2522  "Cannot get force/torque measures.");
2523  }
2524  return H; // Here to avoid a warning, but should never be called
2525 }
2526 
2533 {
2534  InitTry;
2535  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0) );
2536  std::cout << "Enable joint limits on axis 6..." << std::endl;
2537  CatchPrint();
2538  if (TryStt < 0) {
2539  vpERROR_TRACE ("Cannot enable joint limits on axis 6");
2541  "Cannot enable joint limits on axis 6.");
2542  }
2543 }
2544 
2555 {
2556  InitTry;
2557  Try( PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1) );
2558  std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2559  CatchPrint();
2560  if (TryStt < 0) {
2561  vpERROR_TRACE ("Cannot disable joint limits on axis 6");
2563  "Cannot disable joint limits on axis 6.");
2564  }
2565 }
2566 
2574 void
2576 {
2579 
2580  return;
2581 }
2582 
2602 void
2604 {
2605  maxRotationVelocity_joint6 = w6_max;
2606  return;
2607 }
2608 
2615 double
2617 {
2618  return maxRotationVelocity_joint6;
2619 }
2620 
2628 {
2629  InitTry;
2630  Try( PrimitivePneumaticGripper_Viper650(1) );
2631  std::cout << "Open the pneumatic gripper..." << std::endl;
2632  CatchPrint();
2633  if (TryStt < 0) {
2635  "Cannot open the gripper.");
2636  }
2637 }
2638 
2647 {
2648  InitTry;
2649  Try( PrimitivePneumaticGripper_Viper650(0) );
2650  std::cout << "Close the pneumatic gripper..." << std::endl;
2651  CatchPrint();
2652  if (TryStt < 0) {
2654  "Cannot close the gripper.");
2655  }
2656 }
2657 
2658 #elif !defined(VISP_BUILD_SHARED_LIBS)
2659 // Work arround to avoid warning: libvisp_robot.a(vpRobotViper650.cpp.o) has no symbols
2660 void dummy_vpRobotViper650() {};
2661 #endif
static const double defaultPositioningVelocity
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpViper.cpp:1002
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:157
Error that can be emited by the vpRobot class and its derivates.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
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:157
#define vpERROR_TRACE
Definition: vpDebug.h:391
void setPositioningVelocity(const double velocity)
vpColVector getForceTorque() const
double maxRotationVelocity
Definition: vpRobot.h:95
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
void setMaxRotationVelocityJoint6(double w6_max)
Initialize the position controller.
Definition: vpRobot.h:69
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
void get_cVe(vpVelocityTwistMatrix &cVe) const
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:84
vpControlFrameType
Definition: vpRobot.h:76
vpRxyzVector erc
Definition: vpViper.h:157
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position)
void closeGripper() const
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
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:127
double getTime() const
Implementation of a rotation matrix and operations on such kind of matrices.
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:68
Emergency stop activated.
vpRobotStateType
Definition: vpRobot.h:64
bool verbose_
Definition: vpRobot.h:113
vpTranslationVector etc
Definition: vpViper.h:156
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1279
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRowVector t() const
vpColVector joint_max
Definition: vpViper.h:169
VISP_EXPORT void sleepMs(double t)
Definition: vpTime.cpp:266
Modelisation of the ADEPT Viper 650 robot.
Definition: vpViper650.h:102
void enableJoint6Limits() const
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:616
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1596
double getPositioningVelocity(void) const
Manual control mode activated when the dead man switch is in use.
void init(void)
Definition: vpViper650.cpp:132
Implementation of a velocity twist matrix and operations on such kind of matrices.
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.h:127
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition: vpViper.cpp:578
static double rad(double deg)
Definition: vpMath.h:104
void get_fJe(vpMatrix &fJe)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpViper.cpp:1194
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:262
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:948
static double deg(double rad)
Definition: vpMath.h:97
void biasForceTorqueSensor() 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:93
vpHomogeneousMatrix inverse() const
void move(const std::string &filename)
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:141
void disableJoint6Limits() const
double getMaxRotationVelocityJoint6() const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
void setMaxRotationVelocity(double w_max)
static bool readPosFile(const std::string &filename, vpColVector &q)
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRzyzVector.h:151
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void get_cMe(vpHomogeneousMatrix &cMe) const
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
void rad2deg()
Definition: vpColVector.h:210
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:151
void get_eJe(vpMatrix &eJe)
bool getPowerState() const
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:225
vpColVector joint_min
Definition: vpViper.h:170