Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
vpAfma6.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 
46 #include <sstream>
47 #include <iostream>
48 
49 #include <visp3/core/vpDebug.h>
50 #include <visp3/core/vpVelocityTwistMatrix.h>
51 #include <visp3/robot/vpRobotException.h>
52 #include <visp3/core/vpXmlParserCamera.h>
53 #include <visp3/core/vpCameraParameters.h>
54 #include <visp3/core/vpRxyzVector.h>
55 #include <visp3/core/vpTranslationVector.h>
56 #include <visp3/core/vpRotationMatrix.h>
57 #include <visp3/robot/vpAfma6.h>
58 
59 /* ----------------------------------------------------------------------- */
60 /* --- STATIC ------------------------------------------------------------ */
61 /* ---------------------------------------------------------------------- */
62 
63 static const char *opt_Afma6[] = {"JOINT_MAX","JOINT_MIN","LONG_56","COUPL_56",
64  "CAMERA", "eMc_ROT_XYZ","eMc_TRANS_XYZ",
65  NULL};
66 
67 #ifdef VISP_HAVE_AFMA6_DATA
68 const std::string vpAfma6::CONST_AFMA6_FILENAME =
69  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_Afma6.cnf");
70 
72  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_without_distortion_Afma6.cnf");
73 
75  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_with_distortion_Afma6.cnf");
76 
78  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_without_distortion_Afma6.cnf");
79 
81  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_with_distortion_Afma6.cnf");
82 
84  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_without_distortion_Afma6.cnf");
85 
87  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_with_distortion_Afma6.cnf");
88 
90  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_without_distortion_Afma6.cnf");
91 
93  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_with_distortion_Afma6.cnf");
94 
95 const std::string vpAfma6::CONST_CAMERA_AFMA6_FILENAME =
96  std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_camera_Afma6.xml");
97 
98 #endif // VISP_HAVE_AFMA6_DATA
99 
100 const char * const vpAfma6::CONST_CCMOP_CAMERA_NAME = "Dragonfly2-8mm-ccmop";
101 const char * const vpAfma6::CONST_GRIPPER_CAMERA_NAME = "Dragonfly2-6mm-gripper";
102 const char * const vpAfma6::CONST_VACUUM_CAMERA_NAME = "Dragonfly2-6mm-vacuum";
103 const char * const vpAfma6::CONST_GENERIC_CAMERA_NAME = "Generic-camera";
104 
106 
107 const unsigned int vpAfma6::njoint = 6;
108 
115  : _coupl_56(0), _long_56(0), _etc(), _erc(), _eMc(),
116  tool_current(vpAfma6::defaultTool),
117  projModel(vpCameraParameters::perspectiveProjWithoutDistortion)
118 {
119  // Set the default parameters in case of the config files are not available.
120 
121  //
122  // Geometric model constant parameters
123  //
124  // coupling between join 5 and 6
125  this->_coupl_56 = 0.009091;
126  // distance between join 5 and 6
127  this->_long_56 = -0.06924;
128  // Camera extrinsic parameters: effector to camera frame
129  this->_eMc.eye(); // Default values are initialized ...
130  // ... in init (vpAfma6::vpAfma6ToolType tool,
131  // vpCameraParameters::vpCameraParametersProjType projModel)
132  // Maximal value of the joints
133  this->_joint_max[0] = 0.7001;
134  this->_joint_max[1] = 0.5201;
135  this->_joint_max[2] = 0.4601;
136  this->_joint_max[3] = 2.7301;
137  this->_joint_max[4] = 2.4801;
138  this->_joint_max[5] = 1.5901;
139  // Minimal value of the joints
140  this->_joint_min[0] = -0.6501;
141  this->_joint_min[1] = -0.6001;
142  this->_joint_min[2] = -0.5001;
143  this->_joint_min[3] = -2.7301;
144  this->_joint_min[4] = -0.1001;
145  this->_joint_min[5] = -1.5901;
146 
147  init();
148 
149 }
150 
155 void
157 {
158  this->init ( vpAfma6::defaultTool);
159  return;
160 }
161 
173 void
174 vpAfma6::init (const std::string &camera_extrinsic_parameters,
175  const std::string &camera_intrinsic_parameters)
176 {
177  this->parseConfigFile (camera_extrinsic_parameters);
178 
179  this->parseConfigFile (camera_intrinsic_parameters);
180 }
181 
211 void
212 vpAfma6::init(vpAfma6::vpAfma6ToolType tool, const std::string &filename)
213 {
214  this->setToolType(tool);
215  this->parseConfigFile(filename.c_str());
216 }
217 
227 void
228 vpAfma6::init (const std::string &camera_extrinsic_parameters)
229 {
230  this->parseConfigFile (camera_extrinsic_parameters);
231 }
232 
247 void
249 {
250  this->setToolType(tool);
251  this->set_eMc(eMc);
252 }
253 
271 void
274 {
275 
276  this->projModel = proj_model;
277 
278 #ifdef VISP_HAVE_AFMA6_DATA
279  // Read the robot parameters from files
280  std::string filename_eMc;
281  switch (tool) {
282  case vpAfma6::TOOL_CCMOP: {
283  switch(projModel) {
286  break;
289  break;
290  }
291  break;
292  }
293  case vpAfma6::TOOL_GRIPPER: {
294  switch(projModel) {
297  break;
300  break;
301  }
302  break;
303  }
304  case vpAfma6::TOOL_VACUUM: {
305  switch(projModel) {
308  break;
311  break;
312  }
313  break;
314  }
316  switch(projModel) {
319  break;
322  break;
323  }
324  break;
325  }
326  default: {
327  vpERROR_TRACE ("This error should not occur!");
328  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
329  // "que les specs de la classe ont ete modifiee, "
330  // "et que le code n'a pas ete mis a jour "
331  // "correctement.");
332  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
333  // "vpAfma6::vpAfma6ToolType, et controlez que "
334  // "tous les cas ont ete pris en compte dans la "
335  // "fonction init(camera).");
336  break;
337  }
338  }
339 
340  this->init (vpAfma6::CONST_AFMA6_FILENAME, filename_eMc);
341 
342 #else // VISP_HAVE_AFMA6_DATA
343 
344  // Use here default values of the robot constant parameters.
345  switch (tool) {
346  case vpAfma6::TOOL_CCMOP: {
347  switch(projModel) {
349  _erc[0] = vpMath::rad(164.35); // rx
350  _erc[1] = vpMath::rad( 89.64); // ry
351  _erc[2] = vpMath::rad(-73.05); // rz
352  _etc[0] = 0.0117; // tx
353  _etc[1] = 0.0033; // ty
354  _etc[2] = 0.2272; // tz
355  break;
357  _erc[0] = vpMath::rad(33.54); // rx
358  _erc[1] = vpMath::rad(89.34); // ry
359  _erc[2] = vpMath::rad(57.83); // rz
360  _etc[0] = 0.0373; // tx
361  _etc[1] = 0.0024; // ty
362  _etc[2] = 0.2286; // tz
363  break;
364  }
365  break;
366  }
367  case vpAfma6::TOOL_GRIPPER: {
368  switch(projModel) {
370  _erc[0] = vpMath::rad( 88.33); // rx
371  _erc[1] = vpMath::rad( 72.07); // ry
372  _erc[2] = vpMath::rad( 2.53); // rz
373  _etc[0] = 0.0783; // tx
374  _etc[1] = 0.1234; // ty
375  _etc[2] = 0.1638; // tz
376  break;
378  _erc[0] = vpMath::rad(86.69); // rx
379  _erc[1] = vpMath::rad(71.93); // ry
380  _erc[2] = vpMath::rad( 4.17); // rz
381  _etc[0] = 0.1034; // tx
382  _etc[1] = 0.1142; // ty
383  _etc[2] = 0.1642; // tz
384  break;
385  }
386  break;
387  }
388  case vpAfma6::TOOL_VACUUM: {
389  switch(projModel) {
391  _erc[0] = vpMath::rad( 90.40); // rx
392  _erc[1] = vpMath::rad( 75.11); // ry
393  _erc[2] = vpMath::rad( 0.18); // rz
394  _etc[0] = 0.0038; // tx
395  _etc[1] = 0.1281; // ty
396  _etc[2] = 0.1658; // tz
397  break;
399  _erc[0] = vpMath::rad(91.61); // rx
400  _erc[1] = vpMath::rad(76.17); // ry
401  _erc[2] = vpMath::rad(-0.98); // rz
402  _etc[0] = 0.0815; // tx
403  _etc[1] = 0.1162; // ty
404  _etc[2] = 0.1658; // tz
405  break;
406  }
407  break;
408  }
411  switch(projModel) {
414  // set eMc to identity
415  _erc[0] = 0; // rx
416  _erc[1] = 0; // ry
417  _erc[2] = 0; // rz
418  _etc[0] = 0; // tx
419  _etc[1] = 0; // ty
420  _etc[2] = 0; // tz
421  break;
422  }
423  break;
424  }
425  }
426  vpRotationMatrix eRc(_erc);
427  this->_eMc.buildFrom(_etc, eRc);
428 #endif // VISP_HAVE_AFMA6_DATA
429 
430  setToolType(tool);
431  return ;
432 }
433 
434 
461 {
463  fMc = get_fMc(q);
464 
465  return fMc;
466 }
467 
541 int
543  vpColVector & q, const bool &nearest, const bool &verbose) const
544 {
546  double q_[2][6],d[2],t;
547  int ok[2];
548  double cord[6];
549 
550  int nbsol = 0;
551 
552  if (q.getRows() != njoint)
553  q.resize(6);
554 
555 
556  // for(unsigned int i=0;i<3;i++) {
557  // fMe[i][3] = fMc[i][3];
558  // for(int j=0;j<3;j++) {
559  // fMe[i][j] = 0.0;
560  // for (int k=0;k<3;k++) fMe[i][j] += fMc[i][k]*rpi[j][k];
561  // fMe[i][3] -= fMe[i][j]*rpi[j][3];
562  // }
563  // }
564 
565  // std::cout << "\n\nfMc: " << fMc;
566  // std::cout << "\n\neMc: " << _eMc;
567 
568  fMe = fMc * this->_eMc.inverse();
569  // std::cout << "\n\nfMe: " << fMe;
570 
571  if (fMe[2][2] >= .99999f)
572  {
573  vpTRACE("singularity\n");
574  q_[0][4] = q_[1][4] = M_PI/2.f;
575  t = atan2(fMe[0][0],fMe[0][1]);
576  q_[1][3] = q_[0][3] = q[3];
577  q_[1][5] = q_[0][5] = t - q_[0][3];
578 
579  while ((q_[1][5]+vpMath::rad(2)) >= this->_joint_max[5])
580  /* -> a cause du couplage 4/5 */
581  {
582  q_[1][5] -= vpMath::rad(10);
583  q_[1][3] += vpMath::rad(10);
584  }
585  while (q_[1][5] <= this->_joint_min[5])
586  {
587  q_[1][5] += vpMath::rad(10);
588  q_[1][3] -= vpMath::rad(10);
589  }
590  }
591  else if (fMe[2][2] <= -.99999)
592  {
593  vpTRACE("singularity\n");
594  q_[0][4] = q_[1][4] = -M_PI/2;
595  t = atan2(fMe[1][1],fMe[1][0]);
596  q_[1][3] = q_[0][3] = q[3];
597  q_[1][5] = q_[0][5] = q_[0][3] - t;
598  while ((q_[1][5]+vpMath::rad(2)) >= this->_joint_max[5])
599  /* -> a cause du couplage 4/5 */
600  {
601  q_[1][5] -= vpMath::rad(10);
602  q_[1][3] -= vpMath::rad(10);
603  }
604  while (q_[1][5] <= this->_joint_min[5])
605  {
606  q_[1][5] += vpMath::rad(10);
607  q_[1][3] += vpMath::rad(10);
608  }
609  }
610  else
611  {
612  q_[0][3] = atan2(-fMe[0][2],fMe[1][2]);
613  if (q_[0][3] >= 0.0) q_[1][3] = q_[0][3] - M_PI;
614  else q_[1][3] = q_[0][3] + M_PI;
615 
616  q_[0][4] = asin(fMe[2][2]);
617  if (q_[0][4] >= 0.0) q_[1][4] = M_PI - q_[0][4];
618  else q_[1][4] = -M_PI - q_[0][4];
619 
620  q_[0][5] = atan2(-fMe[2][1],fMe[2][0]);
621  if (q_[0][5] >= 0.0) q_[1][5] = q_[0][5] - M_PI;
622  else q_[1][5] = q_[0][5] + M_PI;
623  }
624  q_[0][0] = fMe[0][3] - this->_long_56*cos(q_[0][3]);
625  q_[1][0] = fMe[0][3] - this->_long_56*cos(q_[1][3]);
626  q_[0][1] = fMe[1][3] - this->_long_56*sin(q_[0][3]);
627  q_[1][1] = fMe[1][3] - this->_long_56*sin(q_[1][3]);
628  q_[0][2] = q_[1][2] = fMe[2][3];
629 
630  /* prise en compte du couplage axes 5/6 */
631  q_[0][5] += this->_coupl_56*q_[0][4];
632  q_[1][5] += this->_coupl_56*q_[1][4];
633 
634  for (int j=0;j<2;j++)
635  {
636  ok[j] = 1;
637  // test is position is reachable
638  for (unsigned int i=0;i<6;i++) {
639  if (q_[j][i] < this->_joint_min[i] || q_[j][i] > this->_joint_max[i]) {
640  if (verbose) {
641  if (i < 3)
642  std::cout << "Joint " << i << " not in limits: " << this->_joint_min[i] << " < " << q_[j][i] << " < " << this->_joint_max[i] << std::endl;
643  else
644  std::cout << "Joint " << i << " not in limits: " << vpMath::deg(this->_joint_min[i]) << " < " << vpMath::deg(q_[j][i]) << " < " << vpMath::deg(this->_joint_max[i]) << std::endl;
645  }
646  ok[j] = 0;
647  }
648  }
649  }
650  if (ok[0] == 0)
651  {
652  if (ok[1] == 0) {
653  std::cout << "No solution..." << std::endl;
654  nbsol = 0;
655  return nbsol;
656  }
657  else if (ok[1] == 1) {
658  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
659  nbsol = 1;
660  }
661  }
662  else
663  {
664  if (ok[1] == 0) {
665  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
666  nbsol = 1;
667  }
668  else
669  {
670  nbsol = 2;
671  //vpTRACE("2 solutions\n");
672  for (int j=0;j<2;j++)
673  {
674  d[j] = 0.0;
675  for (unsigned int i=3;i<6;i++)
676  d[j] += (q_[j][i] - q[i]) * (q_[j][i] - q[i]);
677  }
678  if (nearest == true)
679  {
680  if (d[0] <= d[1])
681  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
682  else
683  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
684  }
685  else
686  {
687  if (d[0] <= d[1])
688  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
689  else
690  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
691  }
692  }
693  }
694  for(unsigned int i=0; i<6; i++)
695  q[i] = cord[i] ;
696 
697  return nbsol;
698 }
699 
723 vpAfma6::get_fMc (const vpColVector & q) const
724 {
726  get_fMc(q, fMc);
727 
728  return fMc;
729 }
730 
750 void
752 {
753 
754  // Compute the direct geometric model: fMe = transformation between
755  // fix and end effector frame.
757 
758  get_fMe(q, fMe);
759 
760  fMc = fMe * this->_eMc;
761 
762  return;
763 }
764 
784 void
786 {
787  double q0 = q[0]; // meter
788  double q1 = q[1]; // meter
789  double q2 = q[2]; // meter
790 
791  /* Decouplage liaisons 2 et 3. */
792  double q5 = q[5] - this->_coupl_56 * q[4];
793 
794  double c1 = cos(q[3]);
795  double s1 = sin(q[3]);
796  double c2 = cos(q[4]);
797  double s2 = sin(q[4]);
798  double c3 = cos(q5);
799  double s3 = sin(q5);
800 
801  // Compute the direct geometric model: fMe = transformation betwee
802  // fix and end effector frame.
803  fMe[0][0] = s1*s2*c3 + c1*s3;
804  fMe[0][1] = -s1*s2*s3 + c1*c3;
805  fMe[0][2] = -s1*c2;
806  fMe[0][3] = q0 + this->_long_56*c1;
807 
808  fMe[1][0] = -c1*s2*c3 + s1*s3;
809  fMe[1][1] = c1*s2*s3 + s1*c3;
810  fMe[1][2] = c1*c2;
811  fMe[1][3] = q1 + this->_long_56*s1;
812 
813  fMe[2][0] = c2*c3;
814  fMe[2][1] = -c2*s3;
815  fMe[2][2] = s2;
816  fMe[2][3] = q2;
817 
818  fMe[3][0] = 0;
819  fMe[3][1] = 0;
820  fMe[3][2] = 0;
821  fMe[3][3] = 1;
822 
823  // vpCTRACE << "Effector position fMe: " << std::endl << fMe;
824 
825  return;
826 }
827 
838 void
840 {
841  cMe = this->_eMc.inverse();
842 }
855 {
856  return(this->_eMc);
857 }
858 
868 void
870 {
871  vpHomogeneousMatrix cMe ;
872  get_cMe(cMe) ;
873 
874  cVe.buildFrom(cMe) ;
875 
876  return;
877 }
878 
891 void
892 vpAfma6::get_eJe(const vpColVector &q, vpMatrix &eJe) const
893 {
894 
895  eJe.resize(6,6) ;
896 
897  double s4,c4,s5,c5,s6,c6 ;
898 
899  s4=sin(q[3]); c4=cos(q[3]);
900  s5=sin(q[4]); c5=cos(q[4]);
901  s6=sin(q[5]-this->_coupl_56*q[4]); c6=cos(q[5]-this->_coupl_56*q[4]);
902 
903  eJe = 0;
904  eJe[0][0] = s4*s5*c6+c4*s6;
905  eJe[0][1] = -c4*s5*c6+s4*s6;
906  eJe[0][2] = c5*c6;
907  eJe[0][3] = - this->_long_56*s5*c6;
908 
909  eJe[1][0] = -s4*s5*s6+c4*c6;
910  eJe[1][1] = c4*s5*s6+s4*c6;
911  eJe[1][2] = -c5*s6;
912  eJe[1][3] = this->_long_56*s5*s6;
913 
914  eJe[2][0] = -s4*c5;
915  eJe[2][1] = c4*c5;
916  eJe[2][2] = s5;
917  eJe[2][3] = this->_long_56*c5;
918 
919  eJe[3][3] = c5*c6;
920  eJe[3][4] = s6;
921 
922  eJe[4][3] = -c5*s6;
923  eJe[4][4] = c6;
924 
925  eJe[5][3] = s5;
926  eJe[5][4] = -this->_coupl_56;
927  eJe[5][5] = 1;
928 
929  return;
930 }
931 
932 
960 void
961 vpAfma6::get_fJe(const vpColVector &q, vpMatrix &fJe) const
962 {
963 
964  fJe.resize(6,6) ;
965 
966  // block superieur gauche
967  fJe[0][0] = fJe[1][1] = fJe[2][2] = 1 ;
968 
969  double s4 = sin(q[3]) ;
970  double c4 = cos(q[3]) ;
971 
972 
973  // block superieur droit
974  fJe[0][3] = - this->_long_56*s4 ;
975  fJe[1][3] = this->_long_56*c4 ;
976 
977 
978  double s5 = sin(q[4]) ;
979  double c5 = cos(q[4]) ;
980  // block inferieur droit
981  fJe[3][4] = c4 ; fJe[3][5] = -s4*c5 ;
982  fJe[4][4] = s4 ; fJe[4][5] = c4*c5 ;
983  fJe[5][3] = 1 ; fJe[5][5] = s5 ;
984 
985  // coupling between joint 5 and 6
986  fJe[3][4] += this->_coupl_56*s4*c5;
987  fJe[4][4] += -this->_coupl_56*c4*c5;
988  fJe[5][4] += -this->_coupl_56*s5;
989 
990  return;
991 }
992 
993 
1004 {
1005  vpColVector qmin(6);
1006  for (unsigned int i=0; i < 6; i ++)
1007  qmin[i] = this->_joint_min[i];
1008  return qmin;
1009 }
1010 
1021 {
1022  vpColVector qmax(6);
1023  for (unsigned int i=0; i < 6; i ++)
1024  qmax[i] = this->_joint_max[i];
1025  return qmax;
1026 }
1027 
1034 double
1036 {
1037  return _coupl_56;
1038 }
1039 
1046 double
1048 {
1049  return _long_56;
1050 }
1051 
1052 
1062 void
1063 vpAfma6::parseConfigFile (const std::string &filename)
1064 {
1065  double rot_eMc[3]; // rotation
1066  double trans_eMc[3]; // translation
1067 
1068  std::ifstream fdconfig(filename.c_str(), std::ios::in);
1069 
1070  if(! fdconfig.is_open()) {
1072  "Impossible to read the config file: %s", filename.c_str());
1073  }
1074 
1075  std::string line;
1076  int lineNum = 0;
1077  bool get_rot_eMc = false;
1078  bool get_trans_eMc = false;
1079  int code;
1080 
1081  while(std::getline(fdconfig, line)) {
1082  lineNum ++;
1083  if((line.compare(0, 1, "#") == 0)) { // skip comment
1084  continue;
1085  }
1086  std::istringstream ss(line);
1087  std::string key;
1088  ss >> key;
1089 
1090  for (code = 0; NULL != opt_Afma6[code]; ++ code) {
1091  if (key.compare(opt_Afma6[code]) == 0) {
1092  break;
1093  }
1094  }
1095 
1096  switch(code)
1097  {
1098  case 0:
1099  ss >> this->_joint_max[0] >> this->_joint_max[1] >> this->_joint_max[2]
1100  >> this->_joint_max[3] >> this->_joint_max[4] >> this->_joint_max[5];
1101  break;
1102 
1103  case 1:
1104  ss >> this->_joint_min[0] >> this->_joint_min[1] >> this->_joint_min[2]
1105  >> this->_joint_min[3] >> this->_joint_min[4] >> this->_joint_min[5];
1106  break;
1107 
1108  case 2:
1109  ss >> this->_long_56;
1110  break;
1111 
1112  case 3:
1113  ss >> this->_coupl_56;
1114  break;
1115 
1116  case 4:
1117  break; // Nothing to do: camera name
1118 
1119  case 5:
1120  ss >> rot_eMc[0] >> rot_eMc[1] >> rot_eMc[2];
1121 
1122  // Convert rotation from degrees to radians
1123  rot_eMc[0] *= M_PI / 180.0;
1124  rot_eMc[1] *= M_PI / 180.0;
1125  rot_eMc[2] *= M_PI / 180.0;
1126  get_rot_eMc = true;
1127  break;
1128 
1129  case 6:
1130  ss >> trans_eMc[0] >> trans_eMc[1] >> trans_eMc[2];
1131  get_trans_eMc = true;
1132  break;
1133 
1134  default:
1136  "Bad configuration file %s line #%d",
1137  filename.c_str(), lineNum));
1138  } /* SWITCH */
1139  } /* WHILE */
1140 
1141  // Compute the eMc matrix from the translations and rotations
1142  if (get_rot_eMc && get_trans_eMc) {
1143  for (unsigned int i=0; i < 3; i ++) {
1144  _erc[i] = rot_eMc[i];
1145  _etc[i] = trans_eMc[i];
1146  }
1147 
1148  vpRotationMatrix eRc(_erc);
1149  this->_eMc.buildFrom(_etc, eRc);
1150  }
1151 
1152  fdconfig.close();
1153 }
1154 
1163 void
1165 {
1166  this->_eMc = eMc;
1167  this->_etc = eMc.getTranslationVector();
1168 
1169  vpRotationMatrix R(eMc);
1170  this->_erc.buildFrom(R);
1171 }
1172 
1234 void
1236  const unsigned int &image_width,
1237  const unsigned int &image_height) const
1238 {
1239 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_AFMA6_DATA)
1240  vpXmlParserCamera parser;
1241  switch (getToolType()) {
1242  case vpAfma6::TOOL_CCMOP: {
1243  std::cout << "Get camera parameters for camera \""
1244  << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl
1245  << "from the XML file: \""
1246  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1247  if (parser.parse(cam,
1250  projModel,
1251  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1253  "Impossible to read the camera parameters.");
1254  }
1255  break;
1256  }
1257  case vpAfma6::TOOL_GRIPPER: {
1258  std::cout << "Get camera parameters for camera \""
1259  << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl
1260  << "from the XML file: \""
1261  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1262  if (parser.parse(cam,
1265  projModel,
1266  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1268  "Impossible to read the camera parameters.");
1269  }
1270  break;
1271  }
1272  case vpAfma6::TOOL_VACUUM: {
1273  std::cout << "Get camera parameters for camera \""
1274  << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl
1275  << "from the XML file: \""
1276  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1277  if (parser.parse(cam,
1280  projModel,
1281  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1283  "Impossible to read the camera parameters.");
1284  }
1285  break;
1286  }
1288  std::cout << "Get camera parameters for camera \""
1289  << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
1290  << "from the XML file: \""
1291  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1292  if (parser.parse(cam,
1295  projModel,
1296  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1298  "Impossible to read the camera parameters.");
1299  }
1300  break;
1301  }
1302  default: {
1303  vpERROR_TRACE ("This error should not occur!");
1304  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
1305  // "que les specs de la classe ont ete modifiee, "
1306  // "et que le code n'a pas ete mis a jour "
1307  // "correctement.");
1308  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
1309  // "vpAfma6::vpAfma6ToolType, et controlez que "
1310  // "tous les cas ont ete pris en compte dans la "
1311  // "fonction init(camera).");
1313  "Impossible to read the camera parameters.");
1314  }
1315  }
1316 #else
1317  // Set default parameters
1318  switch (getToolType()) {
1319  case vpAfma6::TOOL_CCMOP: {
1320  // Set default intrinsic camera parameters for 640x480 images
1321  if (image_width == 640 && image_height == 480) {
1322  std::cout << "Get default camera parameters for camera \""
1323  << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl;
1324  switch(this->projModel) {
1326  cam.initPersProjWithoutDistortion(1108.0, 1110.0, 314.5, 243.2);
1327  break;
1329  cam.initPersProjWithDistortion(1090.6, 1090.0, 310.1, 260.8, -0.2114, 0.2217);
1330  break;
1331  }
1332  }
1333  else {
1334  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1336  "Impossible to read the camera parameters.");
1337  }
1338  break;
1339  }
1340  case vpAfma6::TOOL_GRIPPER: {
1341  // Set default intrinsic camera parameters for 640x480 images
1342  if (image_width == 640 && image_height == 480) {
1343  std::cout << "Get default camera parameters for camera \""
1344  << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl;
1345  switch(this->projModel) {
1347  cam.initPersProjWithoutDistortion(850.9, 853.0, 311.1, 243.6);
1348  break;
1350  cam.initPersProjWithDistortion(837.0, 837.5, 308.7, 251.6, -0.1455, 0.1511);
1351  break;
1352  }
1353  }
1354  else {
1355  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1357  "Impossible to read the camera parameters.");
1358  }
1359  break;
1360  }
1361  case vpAfma6::TOOL_VACUUM: {
1362  // Set default intrinsic camera parameters for 640x480 images
1363  if (image_width == 640 && image_height == 480) {
1364  std::cout << "Get default camera parameters for camera \""
1365  << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl;
1366  switch(this->projModel) {
1368  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1369  break;
1371  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1372  break;
1373  }
1374  }
1375  else {
1376  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1378  "Impossible to read the camera parameters.");
1379  }
1380  break;
1381  }
1383  // Set default intrinsic camera parameters for 640x480 images
1384  if (image_width == 640 && image_height == 480) {
1385  std::cout << "Get default camera parameters for camera \""
1386  << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl;
1387  switch(this->projModel) {
1389  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1390  break;
1392  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1393  break;
1394  }
1395  }
1396  else {
1397  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1399  "Impossible to read the camera parameters.");
1400  }
1401  break;
1402  }
1403  default:
1404  vpERROR_TRACE ("This error should not occur!");
1405  break;
1406  }
1407 #endif
1408  return;
1409 }
1410 
1452 void
1454  const vpImage<unsigned char> &I) const
1455 {
1456  getCameraParameters(cam,I.getWidth(),I.getHeight());
1457 }
1501 void
1503  const vpImage<vpRGBa> &I) const
1504 {
1505  getCameraParameters(cam,I.getWidth(),I.getHeight());
1506 }
1507 
1508 
1518 VISP_EXPORT std::ostream & operator << (std::ostream & os,
1519  const vpAfma6 & afma6)
1520 {
1521  vpRotationMatrix eRc;
1522  afma6._eMc.extract(eRc);
1523  vpRxyzVector rxyz(eRc);
1524 
1525  os
1526  << "Joint Max:" << std::endl
1527  << "\t" << afma6._joint_max[0]
1528  << "\t" << afma6._joint_max[1]
1529  << "\t" << afma6._joint_max[2]
1530  << "\t" << afma6._joint_max[3]
1531  << "\t" << afma6._joint_max[4]
1532  << "\t" << afma6._joint_max[5]
1533  << "\t" << std::endl
1534 
1535  << "Joint Min: " << std::endl
1536  << "\t" << afma6._joint_min[0]
1537  << "\t" << afma6._joint_min[1]
1538  << "\t" << afma6._joint_min[2]
1539  << "\t" << afma6._joint_min[3]
1540  << "\t" << afma6._joint_min[4]
1541  << "\t" << afma6._joint_min[5]
1542  << "\t" << std::endl
1543 
1544  << "Long 5-6: " << std::endl
1545  << "\t" << afma6._long_56
1546  << "\t" << std::endl
1547 
1548  << "Coupling 5-6:" << std::endl
1549  << "\t" << afma6._coupl_56
1550  << "\t" << std::endl
1551 
1552  << "eMc: "<< std::endl
1553  << "\tTranslation (m): "
1554  << afma6._eMc[0][3] << " "
1555  << afma6._eMc[1][3] << " "
1556  << afma6._eMc[2][3]
1557  << "\t" << std::endl
1558  << "\tRotation Rxyz (rad) : "
1559  << rxyz[0] << " "
1560  << rxyz[1] << " "
1561  << rxyz[2]
1562  << "\t" << std::endl
1563  << "\tRotation Rxyz (deg) : "
1564  << vpMath::deg(rxyz[0]) << " "
1565  << vpMath::deg(rxyz[1]) << " "
1566  << vpMath::deg(rxyz[2])
1567  << "\t" << std::endl;
1568 
1569  return os;
1570 }
1571 
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:90
Modelisation of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:76
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
vpRxyzVector buildFrom(const vpRotationMatrix &R)
vpRxyzVector _erc
Definition: vpAfma6.h:206
vpTranslationVector _etc
Definition: vpAfma6.h:205
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpAfma6.cpp:1235
static const unsigned int njoint
Number of joint.
Definition: vpAfma6.h:191
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpAfma6.cpp:869
static const std::string CONST_AFMA6_FILENAME
Definition: vpAfma6.h:83
Error that can be emited by the vpRobot class and its derivates.
Perspective projection without distortion model.
unsigned int getWidth() const
Definition: vpImage.h:226
static const std::string CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:86
void resize(const unsigned int nrows, const unsigned int ncols, const bool flagNullify=true)
Definition: vpArray2D.h:167
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Definition: vpAfma6.cpp:460
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition: vpAfma6.cpp:542
vpAfma6ToolType getToolType() const
Get the current tool type.
Definition: vpAfma6.h:158
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:723
#define vpERROR_TRACE
Definition: vpDebug.h:391
void parseConfigFile(const std::string &filename)
Definition: vpAfma6.cpp:1063
static const std::string CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:85
double _coupl_56
Definition: vpAfma6.h:200
static const std::string CONST_CAMERA_AFMA6_FILENAME
Definition: vpAfma6.h:92
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
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpAfma6.h:214
XML parser to load and save intrinsic camera parameters.
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpAfma6.cpp:785
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition: vpAfma6.h:189
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:91
static const char *const CONST_GRIPPER_CAMERA_NAME
Definition: vpAfma6.h:102
Implementation of a rotation matrix and operations on such kind of matrices.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpAfma6.h:125
vpColVector getJointMin() const
Definition: vpAfma6.cpp:1003
vpHomogeneousMatrix get_eMc() const
Definition: vpAfma6.cpp:854
vpTranslationVector getTranslationVector() const
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static const std::string CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:88
#define vpTRACE
Definition: vpDebug.h:414
static const std::string CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:89
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:839
Generic class defining intrinsic camera parameters.
vpColVector getJointMax() const
Definition: vpAfma6.cpp:1020
void extract(vpRotationMatrix &R) const
friend std::ostream & operator<<(std::ostream &s, const vpArray2D< Type > &A)
Definition: vpArray2D.h:267
Implementation of a velocity twist matrix and operations on such kind of matrices.
unsigned int getRows() const
Return the number of rows of the 2D array.
Definition: vpArray2D.h:152
vpAfma6()
Definition: vpAfma6.cpp:114
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
Definition: vpMath.h:104
static const std::string CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:84
double getLong56() const
Definition: vpAfma6.cpp:1047
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
vpHomogeneousMatrix inverse() const
vpHomogeneousMatrix _eMc
Definition: vpAfma6.h:208
unsigned int getHeight() const
Definition: vpImage.h:175
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
void init(void)
Definition: vpAfma6.cpp:156
double _joint_max[6]
Definition: vpAfma6.h:202
int parse(vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, const unsigned int image_width=0, const unsigned int image_height=0)
static const char *const CONST_CCMOP_CAMERA_NAME
Definition: vpAfma6.h:97
static const std::string CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:87
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:961
static const char *const CONST_VACUUM_CAMERA_NAME
Definition: vpAfma6.h:107
void initPersProjWithDistortion(const double px, const double py, const double u0, const double v0, const double kud, const double kdu)
double _joint_min[6]
Definition: vpAfma6.h:203
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:225
static const char *const CONST_GENERIC_CAMERA_NAME
Definition: vpAfma6.h:112
double getCoupl56() const
Definition: vpAfma6.cpp:1035