Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpRobotAfma6.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 Afma6 robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #include <visp3/core/vpConfig.h>
39 
40 #ifdef VISP_HAVE_AFMA6
41 
42 #include <signal.h>
43 #include <stdlib.h>
44 #include <sys/types.h>
45 #include <unistd.h>
46 
47 #include <visp3/core/vpExponentialMap.h>
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpVelocityTwistMatrix.h>
50 #include <visp3/core/vpThetaUVector.h>
51 #include <visp3/core/vpIoTools.h>
52 #include <visp3/core/vpRotationMatrix.h>
53 #include <visp3/robot/vpRobotAfma6.h>
54 #include <visp3/robot/vpRobotException.h>
55 
56 /* ---------------------------------------------------------------------- */
57 /* --- STATIC ----------------------------------------------------------- */
58 /* ---------------------------------------------------------------------- */
59 
60 bool vpRobotAfma6::robotAlreadyCreated = false;
61 
70 
71 /* ---------------------------------------------------------------------- */
72 /* --- EMERGENCY STOP --------------------------------------------------- */
73 /* ---------------------------------------------------------------------- */
74 
82 void emergencyStopAfma6(int signo)
83 {
84  std::cout << "Stop the Afma6 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_Afma6();
103  PrimitiveSTOP_Afma6();
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 
155 vpRobotAfma6::vpRobotAfma6 (bool verbose)
156  :
157  vpAfma6 (),
158  vpRobot ()
159 {
160 
161  /*
162  #define SIGHUP 1 // hangup
163  #define SIGINT 2 // interrupt (rubout)
164  #define SIGQUIT 3 // quit (ASCII FS)
165  #define SIGILL 4 // illegal instruction (not reset when caught)
166  #define SIGTRAP 5 // trace trap (not reset when caught)
167  #define SIGIOT 6 // IOT instruction
168  #define SIGABRT 6 // used by abort, replace SIGIOT in the future
169  #define SIGEMT 7 // EMT instruction
170  #define SIGFPE 8 // floating point exception
171  #define SIGKILL 9 // kill (cannot be caught or ignored)
172  #define SIGBUS 10 // bus error
173  #define SIGSEGV 11 // segmentation violation
174  #define SIGSYS 12 // bad argument to system call
175  #define SIGPIPE 13 // write on a pipe with no one to read it
176  #define SIGALRM 14 // alarm clock
177  #define SIGTERM 15 // software termination signal from kill
178  */
179 
180  signal(SIGINT, emergencyStopAfma6);
181  signal(SIGBUS, emergencyStopAfma6) ;
182  signal(SIGSEGV, emergencyStopAfma6) ;
183  signal(SIGKILL, emergencyStopAfma6);
184  signal(SIGQUIT, emergencyStopAfma6);
185 
186  setVerbose(verbose);
187  if (verbose_)
188  std::cout << "Open communication with MotionBlox.\n";
189  try {
190  this->init();
192  }
193  catch(...) {
194  // vpERROR_TRACE("Error caught") ;
195  throw ;
196  }
197  positioningVelocity = defaultPositioningVelocity ;
198 
199  vpRobotAfma6::robotAlreadyCreated = true;
200 
201  return ;
202 }
203 
204 
205 /* ------------------------------------------------------------------------ */
206 /* --- INITIALISATION ----------------------------------------------------- */
207 /* ------------------------------------------------------------------------ */
208 
228 void
230 {
231  InitTry;
232 
233  // Initialise private variables used to compute the measured velocities
234  q_prev_getvel.resize(6);
235  q_prev_getvel = 0;
236  time_prev_getvel = 0;
237  first_time_getvel = true;
238 
239  // Initialise private variables used to compute the measured displacement
240  q_prev_getdis.resize(6);
241  q_prev_getdis = 0;
242  first_time_getdis = true;
243 
244  // Initialize the firewire connection
245  Try( InitializeConnection(verbose_) );
246 
247  // Connect to the servoboard using the servo board GUID
248  Try( InitializeNode_Afma6() );
249 
250  Try( PrimitiveRESET_Afma6() );
251 
252  // Update the eMc matrix in the low level controller
254 
255  // Look if the power is on or off
256  UInt32 HIPowerStatus;
257  UInt32 EStopStatus;
258  Try( PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
259  &HIPowerStatus));
260  CAL_Wait(0.1);
261 
262  // Print the robot status
263  if (verbose_) {
264  std::cout << "Robot status: ";
265  switch(EStopStatus) {
266  case ESTOP_AUTO:
267  case ESTOP_MANUAL:
268  if (HIPowerStatus == 0)
269  std::cout << "Power is OFF" << std::endl;
270  else
271  std::cout << "Power is ON" << std::endl;
272  break;
273  case ESTOP_ACTIVATED:
274  std::cout << "Emergency stop is activated" << std::endl;
275  break;
276  default:
277  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
278  std::cout << "You have to call Adept for maintenance..." << std::endl;
279  // Free allocated resources
280  }
281  std::cout << std::endl;
282  }
283  // get real joint min/max from the MotionBlox
284  Try( PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max) );
285 // for (unsigned int i=0; i < njoint; i++) {
286 // printf("axis %d: joint min %lf, max %lf\n", i, _joint_min[i], _joint_max[i]);
287 // }
288 
289  // If an error occur in the low level controller, goto here
290  //CatchPrint();
291  Catch();
292 
293  // Test if an error occurs
294  if (TryStt == -20001)
295  printf("No connection detected. Check if the robot is powered on \n"
296  "and if the firewire link exist between the MotionBlox and this computer.\n");
297  else if (TryStt == -675)
298  printf(" Timeout enabling power...\n");
299 
300  if (TryStt < 0) {
301  // Power off the robot
302  PrimitivePOWEROFF_Afma6();
303  // Free allocated resources
304  ShutDownConnection();
305 
306  std::cout << "Cannot open connection with the motionblox..." << std::endl;
308  "Cannot open connection with the motionblox");
309  }
310  return ;
311 }
312 
349 void
352 {
353  InitTry;
354  // Read the robot constants from files
355  // - joint [min,max], coupl_56, long_56
356  // - camera extrinsic parameters relative to eMc
357  vpAfma6::init(tool, projModel);
358 
359  // Set the robot constant (coupl_56, long_56) in the MotionBlox
360  Try( PrimitiveROBOT_CONST_Afma6(_coupl_56, _long_56) );
361 
362  // Set the camera constant (eMc pose) in the MotionBlox
363  double eMc_pose[6];
364  for (unsigned int i=0; i < 3; i ++) {
365  eMc_pose[i] = _etc[i]; // translation in meters
366  eMc_pose[i+3] = _erc[i]; // rotation in rad
367  }
368  // Update the eMc pose in the low level controller
369  Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
370 
371  // get real joint min/max from the MotionBlox
372  Try( PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max) );
373 // for (unsigned int i=0; i < njoint; i++) {
374 // printf("axis %d: joint min %lf, max %lf\n", i, _joint_min[i], _joint_max[i]);
375 // }
376 
377  setToolType(tool);
378 
379  CatchPrint();
380  return ;
381 }
382 
394 void
396 {
397  InitTry;
398  // Set camera extrinsic parameters equal to eMc
399  this->vpAfma6::set_eMc(eMc);
400 
401  // Set the camera constant (eMc pose) in the MotionBlox
402  double eMc_pose[6];
403  for (unsigned int i=0; i < 3; i ++) {
404  eMc_pose[i] = _etc[i]; // translation in meters
405  eMc_pose[i+3] = _erc[i]; // rotation in rad
406  }
407  // Update the eMc pose in the low level controller
408  Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
409 
410  CatchPrint();
411 }
412 
448 void
450 {
451  InitTry;
452  // Read the robot constants from files
453  // - joint [min,max], coupl_56, long_56
454  // ans set camera extrinsic parameters equal to eMc
455  vpAfma6::init(tool, eMc);
456 
457  // Set the robot constant (coupl_56, long_56) in the MotionBlox
458  Try( PrimitiveROBOT_CONST_Afma6(_coupl_56, _long_56) );
459 
460  // Set the camera constant (eMc pose) in the MotionBlox
461  double eMc_pose[6];
462  for (unsigned int i=0; i < 3; i ++) {
463  eMc_pose[i] = _etc[i]; // translation in meters
464  eMc_pose[i+3] = _erc[i]; // rotation in rad
465  }
466  // Update the eMc pose in the low level controller
467  Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
468 
469  // get real joint min/max from the MotionBlox
470  Try( PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max) );
471 
472  setToolType(tool);
473 
474  CatchPrint();
475 }
476 
527 void
528 vpRobotAfma6::init (vpAfma6::vpAfma6ToolType tool, const std::string &filename)
529 {
530  InitTry;
531  // Read the robot constants from files
532  // - joint [min,max], coupl_56, long_56
533  // ans set camera extrinsic parameters from file name
534  vpAfma6::init(tool, filename);
535 
536  // Set the robot constant (coupl_56, long_56) in the MotionBlox
537  Try( PrimitiveROBOT_CONST_Afma6(_coupl_56, _long_56) );
538 
539  // Set the camera constant (eMc pose) in the MotionBlox
540  double eMc_pose[6];
541  for (unsigned int i=0; i < 3; i ++) {
542  eMc_pose[i] = _etc[i]; // translation in meters
543  eMc_pose[i+3] = _erc[i]; // rotation in rad
544  }
545  // Update the eMc pose in the low level controller
546  Try( PrimitiveCAMERA_CONST_Afma6(eMc_pose) );
547 
548  // get real joint min/max from the MotionBlox
549  Try( PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max) );
550 
551  setToolType(tool);
552 
553  CatchPrint();
554 }
555 
556 /* ------------------------------------------------------------------------ */
557 /* --- DESTRUCTOR --------------------------------------------------------- */
558 /* ------------------------------------------------------------------------ */
559 
567 {
568  InitTry;
569 
571 
572  // Look if the power is on or off
573  UInt32 HIPowerStatus;
574  Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
575  &HIPowerStatus));
576  CAL_Wait(0.1);
577 
578 // if (HIPowerStatus == 1) {
579 // fprintf(stdout, "Power OFF the robot\n");
580 // fflush(stdout);
581 
582 // Try( PrimitivePOWEROFF_Afma6() );
583 // }
584 
585  // Free allocated resources
586  ShutDownConnection();
587 
588  vpRobotAfma6::robotAlreadyCreated = false;
589 
590  CatchPrint();
591  return;
592 }
593 
594 
595 
596 
605 {
606  InitTry;
607 
608  switch (newState) {
609  case vpRobot::STATE_STOP: {
611  Try( PrimitiveSTOP_Afma6() );
612  }
613  break;
614  }
617  std::cout << "Change the control mode from velocity to position control.\n";
618  Try( PrimitiveSTOP_Afma6() );
619  }
620  else {
621  //std::cout << "Change the control mode from stop to position control.\n";
622  }
623  this->powerOn();
624  break;
625  }
628  std::cout << "Change the control mode from stop to velocity control.\n";
629  }
630  this->powerOn();
631  break;
632  }
633  default:
634  break ;
635  }
636 
637  CatchPrint();
638 
639  return vpRobot::setRobotState (newState);
640 }
641 
642 
643 /* ------------------------------------------------------------------------ */
644 /* --- STOP --------------------------------------------------------------- */
645 /* ------------------------------------------------------------------------ */
646 
654 void
656 {
657  InitTry;
658  Try( PrimitiveSTOP_Afma6() );
660 
661  CatchPrint();
662  if (TryStt < 0) {
663  vpERROR_TRACE ("Cannot stop robot motion");
665  "Cannot stop robot motion.");
666  }
667 }
668 
678 void
680 {
681  InitTry;
682 
683  // Look if the power is on or off
684  UInt32 HIPowerStatus;
685  UInt32 EStopStatus;
686  bool firsttime = true;
687  unsigned int nitermax = 10;
688 
689  for (unsigned int i=0; i<nitermax; i++) {
690  Try( PrimitiveSTATUS_Afma6(NULL, NULL, &EStopStatus, NULL, NULL, NULL,
691  &HIPowerStatus));
692  if (EStopStatus == ESTOP_AUTO) {
693  break; // exit for loop
694  }
695  else if (EStopStatus == ESTOP_MANUAL) {
696  break; // exit for loop
697  }
698  else if (EStopStatus == ESTOP_ACTIVATED) {
699  if (firsttime) {
700  std::cout << "Emergency stop is activated! \n"
701  << "Check the emergency stop button and push the yellow button before continuing." << std::endl;
702  firsttime = false;
703  }
704  fprintf(stdout, "Remaining time %us \r", nitermax-i);
705  fflush(stdout);
706  CAL_Wait(1);
707  }
708  else {
709  std::cout << "Sorry there is an error on the emergency chain." << std::endl;
710  std::cout << "You have to call Adept for maintenance..." << std::endl;
711  // Free allocated resources
712  ShutDownConnection();
713  exit(0);
714  }
715  }
716 
717  if (EStopStatus == ESTOP_ACTIVATED)
718  std::cout << std::endl;
719 
720  if (EStopStatus == ESTOP_ACTIVATED) {
721  std::cout << "Sorry, cannot power on the robot." << std::endl;
723  "Cannot power on the robot.");
724  }
725 
726  if (HIPowerStatus == 0) {
727  fprintf(stdout, "Power ON the Afma6 robot\n");
728  fflush(stdout);
729 
730  Try( PrimitivePOWERON_Afma6() );
731  }
732 
733  CatchPrint();
734  if (TryStt < 0) {
735  vpERROR_TRACE ("Cannot power on the robot");
737  "Cannot power off the robot.");
738  }
739 }
740 
750 void
752 {
753  InitTry;
754 
755  // Look if the power is on or off
756  UInt32 HIPowerStatus;
757  Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
758  &HIPowerStatus));
759  CAL_Wait(0.1);
760 
761  if (HIPowerStatus == 1) {
762  fprintf(stdout, "Power OFF the Afma6 robot\n");
763  fflush(stdout);
764 
765  Try( PrimitivePOWEROFF_Afma6() );
766  }
767 
768  CatchPrint();
769  if (TryStt < 0) {
770  vpERROR_TRACE ("Cannot power off the robot");
772  "Cannot power off the robot.");
773  }
774 }
775 
787 bool
789 {
790  InitTry;
791  bool status = false;
792  // Look if the power is on or off
793  UInt32 HIPowerStatus;
794  Try( PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, NULL,
795  &HIPowerStatus));
796  CAL_Wait(0.1);
797 
798  if (HIPowerStatus == 1) {
799  status = true;
800  }
801 
802  CatchPrint();
803  if (TryStt < 0) {
804  vpERROR_TRACE ("Cannot get the power status");
806  "Cannot get the power status.");
807  }
808  return status;
809 }
810 
820 void
822 {
823  vpHomogeneousMatrix cMe ;
824  vpAfma6::get_cMe(cMe) ;
825 
826  cVe.buildFrom(cMe) ;
827 }
828 
839 void
841 {
842  vpAfma6::get_cMe(cMe) ;
843 }
844 
845 
856 void
858 {
859 
860  double position[6];
861  double timestamp;
862 
863  InitTry;
864  Try( PrimitiveACQ_POS_Afma6(position, &timestamp) );
865  CatchPrint();
866 
867  vpColVector q(6);
868  for (unsigned int i=0; i < njoint; i++)
869  q[i] = position[i];
870 
871  try
872  {
873  vpAfma6::get_eJe(q, eJe) ;
874  }
875  catch(...)
876  {
877  vpERROR_TRACE("catch exception ") ;
878  throw ;
879  }
880 }
904  void
906 {
907 
908  double position[6];
909  double timestamp;
910 
911  InitTry;
912  Try( PrimitiveACQ_POS_Afma6(position, &timestamp) );
913  CatchPrint();
914 
915  vpColVector q(6);
916  for (unsigned int i=0; i < njoint; i++)
917  q[i] = position[i];
918 
919  try
920  {
921  vpAfma6::get_fJe(q, fJe) ;
922  }
923  catch(...)
924  {
925  vpERROR_TRACE("Error caught");
926  throw ;
927  }
928 }
929 
958 void
960 {
961  positioningVelocity = velocity;
962 }
963 
969 double
971 {
972  return positioningVelocity;
973 }
974 
1049 void
1051  const vpPoseVector & pose )
1052 
1053 {
1054  vpColVector position(6);
1055  vpRxyzVector rxyz;
1056  vpRotationMatrix R;
1057 
1058  R.buildFrom(pose[3], pose[4], pose[5]); //thetau
1059  rxyz.buildFrom(R);
1060 
1061  for (unsigned int i=0; i < 3; i++) {
1062  position[i] = pose[i];
1063  position[i+3] = rxyz[i];
1064  }
1065  if (frame == vpRobot::ARTICULAR_FRAME) {
1067  "Positionning error: "
1068  "Joint frame not implemented for pose positionning.");
1069  }
1070  setPosition (frame, position);
1071 }
1154 void
1156  const vpColVector & position )
1157 {
1158 
1160  {
1161  vpERROR_TRACE ("Robot was not in position-based control\n"
1162  "Modification of the robot state");
1164  }
1165 
1166  double _destination[6];
1167  int error = 0;
1168  double timestamp;
1169 
1170  InitTry;
1171  switch(frame) {
1172  case vpRobot::CAMERA_FRAME : {
1173  double _q[njoint];
1174  Try( PrimitiveACQ_POS_Afma6(_q, &timestamp) );
1175 
1176  vpColVector q(njoint);
1177  for (unsigned int i=0; i < njoint; i++)
1178  q[i] = _q[i];
1179 
1180  // Get fMc from the inverse kinematics
1181  vpHomogeneousMatrix fMc;
1182  vpAfma6::get_fMc(q, fMc);
1183 
1184  // Set cMc from the input position
1185  vpTranslationVector txyz;
1186  vpRxyzVector rxyz;
1187  for (unsigned int i=0; i < 3; i++) {
1188  txyz[i] = position[i];
1189  rxyz[i] = position[i+3];
1190  }
1191 
1192  // Compute cMc2
1193  vpRotationMatrix cRc2(rxyz);
1194  vpHomogeneousMatrix cMc2(txyz, cRc2);
1195 
1196  // Compute the new position to reach: fMc*cMc2
1197  vpHomogeneousMatrix fMc2 = fMc * cMc2;
1198 
1199  // Compute the corresponding joint position from the inverse kinematics
1200  bool nearest = true;
1201  int solution = this->getInverseKinematics(fMc2, q, nearest);
1202  if (solution) { // Position is reachable
1203  for (unsigned int i=0; i < njoint; i ++) {
1204  _destination[i] = q[i];
1205  }
1206  Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1207  Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1208  }
1209  else {
1210  // Cartesian position is out of range
1211  error = -1;
1212  }
1213 
1214  break ;
1215  }
1216  case vpRobot::ARTICULAR_FRAME: {
1217  for (unsigned int i=0; i < njoint; i ++) {
1218  _destination[i] = position[i];
1219  }
1220  Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1221  Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1222  break ;
1223 
1224  }
1225  case vpRobot::REFERENCE_FRAME: {
1226  // Set fMc from the input position
1227  vpTranslationVector txyz;
1228  vpRxyzVector rxyz;
1229  for (unsigned int i=0; i < 3; i++) {
1230  txyz[i] = position[i];
1231  rxyz[i] = position[i+3];
1232  }
1233  // Compute fMc from the input position
1234  vpRotationMatrix fRc(rxyz);
1235  vpHomogeneousMatrix fMc(txyz, fRc);
1236 
1237  // Compute the corresponding joint position from the inverse kinematics
1238  vpColVector q(6);
1239  bool nearest = true;
1240  int solution = this->getInverseKinematics(fMc, q, nearest);
1241  if (solution) { // Position is reachable
1242  for (unsigned int i=0; i < njoint; i ++) {
1243  _destination[i] = q[i];
1244  }
1245  Try( PrimitiveMOVE_Afma6(_destination, positioningVelocity) );
1246  Try( WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000) );
1247  }
1248  else {
1249  // Cartesian position is out of range
1250  error = -1;
1251  }
1252 
1253  break ;
1254  }
1255  case vpRobot::MIXT_FRAME:
1256  {
1257  vpERROR_TRACE ("Positionning error. Mixt frame not implemented");
1259  "Positionning error: "
1260  "Mixt frame not implemented.");
1261  }
1262  }
1263 
1264  CatchPrint();
1265  if (TryStt == InvalidPosition || TryStt == -1023)
1266  std::cout << " : Position out of range.\n";
1267  else if (TryStt < 0)
1268  std::cout << " : Unknown error (see Fabien).\n";
1269  else if (error == -1)
1270  std::cout << "Position out of range.\n";
1271 
1272  if (TryStt < 0 || error < 0) {
1273  vpERROR_TRACE ("Positionning error.");
1275  "Position out of range.");
1276  }
1277 
1278  return ;
1279 }
1280 
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 
1415 void vpRobotAfma6::setPosition(const std::string &filename)
1416 {
1417  vpColVector q;
1418  bool ret;
1419 
1420  ret = this->readPosFile(filename, q);
1421 
1422  if (ret == false) {
1423  vpERROR_TRACE ("Bad position in \"%s\"", filename.c_str());
1425  "Bad position in filename.");
1426  }
1429 }
1430 
1484 void
1486  vpColVector & position, double &timestamp)
1487 {
1488 
1489  InitTry;
1490 
1491  position.resize (6);
1492 
1493  switch (frame) {
1494  case vpRobot::CAMERA_FRAME : {
1495  position = 0;
1496  return;
1497  }
1498  case vpRobot::ARTICULAR_FRAME : {
1499  double _q[njoint];
1500  Try( PrimitiveACQ_POS_Afma6(_q, &timestamp) );
1501  for (unsigned int i=0; i < njoint; i ++) {
1502  position[i] = _q[i];
1503  }
1504 
1505  return;
1506  }
1507  case vpRobot::REFERENCE_FRAME : {
1508  double _q[njoint];
1509  Try( PrimitiveACQ_POS_Afma6(_q, &timestamp) );
1510 
1511  vpColVector q(njoint);
1512  for (unsigned int i=0; i < njoint; i++)
1513  q[i] = _q[i];
1514 
1515  // Compute fMc
1516  vpHomogeneousMatrix fMc;
1517  vpAfma6::get_fMc(q, fMc);
1518 
1519  // From fMc extract the pose
1520  vpRotationMatrix fRc;
1521  fMc.extract(fRc);
1522  vpRxyzVector rxyz;
1523  rxyz.buildFrom(fRc);
1524 
1525  for (unsigned int i=0; i < 3; i++) {
1526  position[i] = fMc[i][3]; // translation x,y,z
1527  position[i+3] = rxyz[i]; // Euler rotation x,y,z
1528  }
1529  break ;
1530  }
1531  case vpRobot::MIXT_FRAME: {
1532  vpERROR_TRACE ("Cannot get position in mixt frame: not implemented");
1534  "Cannot get position in mixt frame: "
1535  "not implemented");
1536  }
1537  }
1538 
1539  CatchPrint();
1540  if (TryStt < 0) {
1541  vpERROR_TRACE ("Cannot get position.");
1543  "Cannot get position.");
1544  }
1545 
1546  return;
1547 }
1552 {
1553  double timestamp;
1554  PrimitiveACQ_TIME_Afma6(&timestamp);
1555  return timestamp;
1556 }
1557 
1568  vpColVector &position)
1569 {
1570  double timestamp;
1571  getPosition(frame, position, timestamp);
1572 }
1573 
1582 void
1584  vpPoseVector &position, double &timestamp)
1585 {
1586  vpColVector posRxyz;
1587  //recupere position en Rxyz
1588  this->getPosition(frame, posRxyz, timestamp);
1589  vpRxyzVector RxyzVect;
1590  for(unsigned int j=0;j<3;j++)
1591  RxyzVect[j]=posRxyz[j+3];
1592  //recupere le vecteur thetaU correspondant
1593  vpThetaUVector RtuVect(RxyzVect);
1594 
1595  //remplit le vpPoseVector avec translation et rotation ThetaU
1596  for(unsigned int j=0;j<3;j++)
1597  {
1598  position[j]=posRxyz[j];
1599  position[j+3]=RtuVect[j];
1600  }
1601 }
1602 
1613  vpPoseVector &position)
1614 {
1615  double timestamp;
1616  getPosition(frame, position, timestamp);
1617 }
1618 
1673 void
1675  const vpColVector & vel)
1676 {
1678  {
1679  vpERROR_TRACE ("Cannot send a velocity to the robot "
1680  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1682  "Cannot send a velocity to the robot "
1683  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1684  }
1685 
1686  vpColVector vel_max(6);
1687 
1688  for (unsigned int i=0; i<3; i++)
1689  vel_max[i] = getMaxTranslationVelocity();
1690  for (unsigned int i=3; i<6; i++)
1691  vel_max[i] = getMaxRotationVelocity();
1692 
1693  vpColVector vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1694 
1695  InitTry;
1696 
1697  switch(frame) {
1698  case vpRobot::CAMERA_FRAME : {
1699  Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPCAM_AFMA6) );
1700  break ;
1701  }
1702  case vpRobot::ARTICULAR_FRAME : {
1703  //Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_AFMA6) );
1704  Try( PrimitiveMOVESPEED_Afma6(vel_sat.data) );
1705  break ;
1706  }
1707  case vpRobot::REFERENCE_FRAME : {
1708  Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPFIX_AFMA6) );
1709  break ;
1710  }
1711  case vpRobot::MIXT_FRAME : {
1712  Try( PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPMIX_AFMA6) );
1713  break ;
1714  }
1715  default: {
1716  vpERROR_TRACE ("Error in spec of vpRobot. "
1717  "Case not taken in account.");
1718  return;
1719  }
1720  }
1721 
1722  Catch();
1723  if (TryStt < 0) {
1724  if (TryStt == VelStopOnJoint) {
1725  Int32 axisInJoint[njoint];
1726  PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint, NULL);
1727  for (unsigned int i=0; i < njoint; i ++) {
1728  if (axisInJoint[i])
1729  std::cout << "\nWarning: Velocity control stopped: axis "
1730  << i+1 << " on joint limit!" <<std::endl;
1731  }
1732  }
1733  else {
1734  printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1735  if (TryString != NULL) {
1736  // The statement is in TryString, but we need to check the validity
1737  printf(" Error sentence %s\n", TryString); // Print the TryString
1738  }
1739  else {
1740  printf("\n");
1741  }
1742  }
1743  }
1744 
1745  return;
1746 }
1747 
1748 
1749 
1750 
1751 
1752 
1753 /* ------------------------------------------------------------------------ */
1754 /* --- GET ---------------------------------------------------------------- */
1755 /* ------------------------------------------------------------------------ */
1756 
1757 
1807 void
1809  vpColVector & velocity, double &timestamp)
1810 {
1811  velocity.resize (6);
1812  velocity = 0;
1813 
1814  double q[6];
1815  vpColVector q_cur(6);
1816  vpHomogeneousMatrix fMc_cur;
1817  vpHomogeneousMatrix cMc; // camera displacement
1818  double time_cur;
1819 
1820  InitTry;
1821 
1822  // Get the current joint position
1823  Try( PrimitiveACQ_POS_Afma6(q, &timestamp) );
1824  time_cur = timestamp;
1825  for (unsigned int i=0; i < njoint; i ++) {
1826  q_cur[i] = q[i];
1827  }
1828 
1829  // Get the camera pose from the direct kinematics
1830  vpAfma6::get_fMc(q_cur, fMc_cur);
1831 
1832  if ( ! first_time_getvel ) {
1833 
1834  switch (frame) {
1835  case vpRobot::CAMERA_FRAME: {
1836  // Compute the displacement of the camera since the previous call
1837  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1838 
1839  // Compute the velocity of the camera from this displacement
1840  velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1841 
1842  break ;
1843  }
1844 
1845  case vpRobot::ARTICULAR_FRAME: {
1846  velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1847  break ;
1848  }
1849 
1850  case vpRobot::REFERENCE_FRAME: {
1851  // Compute the displacement of the camera since the previous call
1852  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1853 
1854  // Compute the velocity of the camera from this displacement
1855  vpColVector v;
1856  v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1857 
1858  // Express this velocity in the reference frame
1859  vpVelocityTwistMatrix fVc(fMc_cur);
1860  velocity = fVc * v;
1861 
1862  break ;
1863  }
1864 
1865  case vpRobot::MIXT_FRAME: {
1866  // Compute the displacement of the camera since the previous call
1867  cMc = fMc_prev_getvel.inverse() * fMc_cur;
1868 
1869  // Compute the ThetaU representation for the rotation
1870  vpRotationMatrix cRc;
1871  cMc.extract(cRc);
1872  vpThetaUVector thetaU;
1873  thetaU.buildFrom(cRc);
1874 
1875  for (unsigned int i=0; i < 3; i++) {
1876  // Compute the translation displacement in the reference frame
1877  velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1878  // Update the rotation displacement in the camera frame
1879  velocity[i+3] = thetaU[i];
1880  }
1881 
1882  // Compute the velocity
1883  velocity /= (time_cur - time_prev_getvel);
1884  break ;
1885  }
1886  }
1887  }
1888  else {
1889  first_time_getvel = false;
1890  }
1891 
1892  // Memorize the camera pose for the next call
1893  fMc_prev_getvel = fMc_cur;
1894 
1895  // Memorize the joint position for the next call
1896  q_prev_getvel = q_cur;
1897 
1898  // Memorize the time associated to the joint position for the next call
1899  time_prev_getvel = time_cur;
1900 
1901 
1902  CatchPrint();
1903  if (TryStt < 0) {
1904  vpERROR_TRACE ("Cannot get velocity.");
1906  "Cannot get velocity.");
1907  }
1908 }
1909 
1919  vpColVector & velocity)
1920 {
1921  double timestamp;
1922  getVelocity(frame, velocity, timestamp);
1923 }
1924 
1925 
1969 {
1970  vpColVector velocity;
1971  getVelocity (frame, velocity, timestamp);
1972 
1973  return velocity;
1974 }
1975 
1985 {
1986  vpColVector velocity;
1987  double timestamp;
1988  getVelocity (frame, velocity, timestamp);
1989 
1990  return velocity;
1991 }
1992 
2041 bool
2042 vpRobotAfma6::readPosFile(const std::string &filename, vpColVector &q)
2043 {
2044  std::ifstream fd(filename.c_str(), std::ios::in);
2045 
2046  if(! fd.is_open()) {
2047  return false;
2048  }
2049 
2050  std::string line;
2051  std::string key("R:");
2052  std::string id("#AFMA6 - Position");
2053  bool pos_found = false;
2054  int lineNum = 0;
2055 
2056  q.resize(njoint);
2057 
2058  while(std::getline(fd, line)) {
2059  lineNum ++;
2060  if (lineNum == 1) {
2061  if(! (line.compare(0, id.size(), id) == 0)) { // check if Afma6 position file
2062  std::cout << "Error: this position file " << filename << " is not for Afma6 robot" << std::endl;
2063  return false;
2064  }
2065  }
2066  if((line.compare(0, 1, "#") == 0)) { // skip comment
2067  continue;
2068  }
2069  if((line.compare(0, key.size(), key) == 0)) { // decode position
2070  // check if there are at least njoint values in the line
2071  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2072  if (chain.size() < njoint+1) // try to split with tab separator
2073  chain = vpIoTools::splitChain(line, std::string("\t"));
2074  if(chain.size() < njoint+1)
2075  continue;
2076 
2077  std::istringstream ss(line);
2078  std::string key_;
2079  ss >> key_;
2080  for (unsigned int i=0; i< njoint; i++)
2081  ss >> q[i];
2082  pos_found = true;
2083  break;
2084  }
2085  }
2086 
2087  // converts rotations from degrees into radians
2088  q[3] = vpMath::rad(q[3]);
2089  q[4] = vpMath::rad(q[4]);
2090  q[5] = vpMath::rad(q[5]);
2091 
2092  fd.close();
2093 
2094  if (!pos_found) {
2095  std::cout << "Error: unable to find a position for Afma6 robot in " << filename << std::endl;
2096  return false;
2097  }
2098 
2099  return true;
2100 }
2101 
2126 bool
2127 vpRobotAfma6::savePosFile(const std::string &filename, const vpColVector &q)
2128 {
2129 
2130  FILE * fd ;
2131  fd = fopen(filename.c_str(), "w") ;
2132  if (fd == NULL)
2133  return false;
2134 
2135  fprintf(fd, "\
2136 #AFMA6 - Position - Version 2.01\n\
2137 #\n\
2138 # R: X Y Z A B C\n\
2139 # Joint position: X, Y, Z: translations in meters\n\
2140 # A, B, C: rotations in degrees\n\
2141 #\n\
2142 #\n\n");
2143 
2144  // Save positions in mm and deg
2145  fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n",
2146  q[0],
2147  q[1],
2148  q[2],
2149  vpMath::deg(q[3]),
2150  vpMath::deg(q[4]),
2151  vpMath::deg(q[5]));
2152 
2153  fclose(fd) ;
2154  return (true);
2155 }
2156 
2167 void
2168 vpRobotAfma6::move(const std::string &filename)
2169 {
2170  vpColVector q;
2171 
2172  this->readPosFile(filename, q) ;
2174  this->setPositioningVelocity(10);
2176 }
2177 
2190 void
2191 vpRobotAfma6::move(const std::string &filename, const double velocity)
2192 {
2193  vpColVector q;
2194 
2195  this->readPosFile(filename, q) ;
2197  this->setPositioningVelocity(velocity);
2199 }
2200 
2207 void
2209 {
2210  InitTry;
2211  Try( PrimitiveGripper_Afma6(1) );
2212  std::cout << "Open the gripper..." << std::endl;
2213  CatchPrint();
2214  if (TryStt < 0) {
2215  vpERROR_TRACE ("Cannot open the gripper");
2217  "Cannot open the gripper.");
2218  }
2219 }
2220 
2228 void
2230 {
2231  InitTry;
2232  Try( PrimitiveGripper_Afma6(0) );
2233  std::cout << "Close the gripper..." << std::endl;
2234  CatchPrint();
2235  if (TryStt < 0) {
2236  vpERROR_TRACE ("Cannot close the gripper");
2238  "Cannot close the gripper.");
2239  }
2240 }
2241 
2255 void
2256 vpRobotAfma6::getCameraDisplacement(vpColVector &displacement)
2257 {
2258  getDisplacement(vpRobot::CAMERA_FRAME, displacement);
2259 }
2271 void
2272 vpRobotAfma6::getArticularDisplacement(vpColVector &displacement)
2273 {
2275 }
2276 
2297 void
2299  vpColVector &displacement)
2300 {
2301  displacement.resize (6);
2302  displacement = 0;
2303 
2304  double q[6];
2305  vpColVector q_cur(6);
2306  vpHomogeneousMatrix fMc_cur, c_prevMc_cur;
2307  double timestamp;
2308 
2309  InitTry;
2310 
2311  // Get the current joint position
2312  Try( PrimitiveACQ_POS_Afma6(q, &timestamp) );
2313  for (unsigned int i=0; i < njoint; i ++) {
2314  q_cur[i] = q[i];
2315  }
2316 
2317  // Compute the camera pose in the reference frame
2318  fMc_cur = get_fMc(q_cur);
2319 
2320  if ( ! first_time_getdis ) {
2321  switch (frame) {
2322  case vpRobot::CAMERA_FRAME: {
2323  // Compute the camera dispacement from the previous pose
2324  c_prevMc_cur = fMc_prev_getdis.inverse() * fMc_cur;
2325 
2327  vpRotationMatrix R;
2328  c_prevMc_cur.extract(t);
2329  c_prevMc_cur.extract(R);
2330 
2331  vpRxyzVector rxyz;
2332  rxyz.buildFrom(R);
2333 
2334  for (unsigned int i=0; i<3; i++) {
2335  displacement[i] = t[i];
2336  displacement[i+3] = rxyz[i];
2337  }
2338  break ;
2339  }
2340 
2341  case vpRobot::ARTICULAR_FRAME: {
2342  displacement = q_cur - q_prev_getdis;
2343  break ;
2344  }
2345 
2346  case vpRobot::REFERENCE_FRAME: {
2347  std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2348  return;
2349  }
2350 
2351  case vpRobot::MIXT_FRAME: {
2352  std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2353  return;
2354  }
2355  }
2356  }
2357  else {
2358  first_time_getdis = false;
2359  }
2360 
2361  // Memorize the joint position for the next call
2362  q_prev_getdis = q_cur;
2363 
2364  // Memorize the pose for the next call
2365  fMc_prev_getdis = fMc_cur;
2366 
2367  CatchPrint();
2368  if (TryStt < 0) {
2369  vpERROR_TRACE ("Cannot get velocity.");
2371  "Cannot get velocity.");
2372  }
2373 }
2374 
2385 bool
2387 {
2388  Int32 axisInJoint[njoint];
2389  bool status = true;
2390  jointsStatus.resize(6);
2391  InitTry;
2392 
2393  Try (PrimitiveSTATUS_Afma6(NULL, NULL, NULL, NULL, NULL, axisInJoint,
2394 NULL));
2395  for (unsigned int i=0; i < njoint; i ++) {
2396  if (axisInJoint[i]){
2397  std::cout << "\nWarning: Velocity control stopped: axis "
2398  << i+1 << " on joint limit!" <<std::endl;
2399  jointsStatus[i] = axisInJoint[i];
2400  status = false;
2401  }
2402  else{
2403  jointsStatus[i] = 0;
2404  }
2405  }
2406 
2407  Catch();
2408  if (TryStt < 0) {
2409  vpERROR_TRACE ("Cannot check joint limits.");
2411  "Cannot check joint limits.");
2412  }
2413 
2414  return status;
2415 
2416 }
2417 
2418 #elif !defined(VISP_BUILD_SHARED_LIBS)
2419 // Work arround to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no symbols
2420 void dummy_vpRobotAfma6() {};
2421 #endif
2422 
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
Modelisation of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:76
static vpColVector inverse(const vpHomogeneousMatrix &M)
bool getPowerState()
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
vpRxyzVector buildFrom(const vpRotationMatrix &R)
vpRxyzVector _erc
Definition: vpAfma6.h:206
bool checkJointLimits(vpColVector &jointsStatus)
vpTranslationVector _etc
Definition: vpAfma6.h:205
static const unsigned int njoint
Number of joint.
Definition: vpAfma6.h:191
void get_eJe(vpMatrix &_eJe)
Error that can be emited by the vpRobot class and its derivates.
void set_eMc(const vpHomogeneousMatrix &eMc)
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition: vpAfma6.cpp:542
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setVerbose(bool verbose)
Definition: vpRobot.h:157
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:723
#define vpERROR_TRACE
Definition: vpDebug.h:391
double _coupl_56
Definition: vpAfma6.h:200
void setPosition(const vpRobot::vpControlFrameType frame, const vpPoseVector &pose)
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
Initialize the position controller.
Definition: vpRobot.h:69
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpAfma6.cpp:892
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:115
Class that defines a generic virtual robot.
Definition: vpRobot.h:58
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:84
vpControlFrameType
Definition: vpRobot.h:76
double getPositioningVelocity(void)
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
vpThetaUVector buildFrom(const vpHomogeneousMatrix &M)
virtual ~vpRobotAfma6(void)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setPositioningVelocity(const double velocity)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition: vpAfma6.h:189
Implementation of a rotation matrix and operations on such kind of matrices.
void init(void)
void get_cMe(vpHomogeneousMatrix &_cMe) const
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpAfma6.h:125
static bool readPosFile(const std::string &filename, vpColVector &q)
static bool savePosFile(const std::string &filename, const vpColVector &q)
Initialize the velocity controller.
Definition: vpRobot.h:68
vpRobotStateType
Definition: vpRobot.h:64
void move(const std::string &filename)
bool verbose_
Definition: vpRobot.h:113
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M)
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:839
void get_fJe(vpMatrix &_fJe)
void extract(vpRotationMatrix &R) const
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1596
Implementation of a velocity twist matrix and operations on such kind of matrices.
static double rad(double deg)
Definition: vpMath.h:104
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
Definition: vpAfma6.cpp:1164
double _long_56
Definition: vpAfma6.h:201
static double deg(double rad)
Definition: vpMath.h:97
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
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:141
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
void init(void)
Definition: vpAfma6.cpp:156
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
double _joint_max[6]
Definition: vpAfma6.h:202
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:961
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
double _joint_min[6]
Definition: vpAfma6.h:203
static const double defaultPositioningVelocity
Definition: vpRobotAfma6.h:258
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
double getTime() const
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:225
void get_cVe(vpVelocityTwistMatrix &_cVe) const