Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
vpAfma6.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See http://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for the Irisa's Afma6 robot.
33  *
34  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
47 #include <iostream>
48 #include <sstream>
49 
50 #include <visp3/core/vpCameraParameters.h>
51 #include <visp3/core/vpDebug.h>
52 #include <visp3/core/vpRotationMatrix.h>
53 #include <visp3/core/vpRxyzVector.h>
54 #include <visp3/core/vpTranslationVector.h>
55 #include <visp3/core/vpVelocityTwistMatrix.h>
56 #include <visp3/core/vpXmlParserCamera.h>
57 #include <visp3/robot/vpAfma6.h>
58 #include <visp3/robot/vpRobotException.h>
59 
60 /* ----------------------------------------------------------------------- */
61 /* --- STATIC ------------------------------------------------------------ */
62 /* ---------------------------------------------------------------------- */
63 
64 static const char *opt_Afma6[] = {"JOINT_MAX", "JOINT_MIN", "LONG_56", "COUPL_56",
65  "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", 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(), tool_current(vpAfma6::defaultTool),
116  projModel(vpCameraParameters::perspectiveProjWithoutDistortion)
117 {
118  // Set the default parameters in case of the config files are not available.
119 
120  //
121  // Geometric model constant parameters
122  //
123  // coupling between join 5 and 6
124  this->_coupl_56 = 0.009091;
125  // distance between join 5 and 6
126  this->_long_56 = -0.06924;
127  // Camera extrinsic parameters: effector to camera frame
128  this->_eMc.eye(); // Default values are initialized ...
129  // ... in init (vpAfma6::vpAfma6ToolType tool,
130  // vpCameraParameters::vpCameraParametersProjType projModel)
131  // Maximal value of the joints
132  this->_joint_max[0] = 0.7001;
133  this->_joint_max[1] = 0.5201;
134  this->_joint_max[2] = 0.4601;
135  this->_joint_max[3] = 2.7301;
136  this->_joint_max[4] = 2.4801;
137  this->_joint_max[5] = 1.5901;
138  // Minimal value of the joints
139  this->_joint_min[0] = -0.6501;
140  this->_joint_min[1] = -0.6001;
141  this->_joint_min[2] = -0.5001;
142  this->_joint_min[3] = -2.7301;
143  this->_joint_min[4] = -0.1001;
144  this->_joint_min[5] = -1.5901;
145 
146  init();
147 }
148 
153 void vpAfma6::init(void)
154 {
155  this->init(vpAfma6::defaultTool);
156  return;
157 }
158 
171 void vpAfma6::init(const std::string &camera_extrinsic_parameters, const std::string &camera_intrinsic_parameters)
172 {
173  this->parseConfigFile(camera_extrinsic_parameters);
174 
175  this->parseConfigFile(camera_intrinsic_parameters);
176 }
177 
208 void vpAfma6::init(vpAfma6::vpAfma6ToolType tool, const std::string &filename)
209 {
210  this->setToolType(tool);
211  this->parseConfigFile(filename.c_str());
212 }
213 
223 void vpAfma6::init(const std::string &camera_extrinsic_parameters)
224 {
225  this->parseConfigFile(camera_extrinsic_parameters);
226 }
227 
244 {
245  this->setToolType(tool);
246  this->set_eMc(eMc);
247 }
248 
267 {
268 
269  this->projModel = proj_model;
270 
271 #ifdef VISP_HAVE_AFMA6_DATA
272  // Read the robot parameters from files
273  std::string filename_eMc;
274  switch (tool) {
275  case vpAfma6::TOOL_CCMOP: {
276  switch (projModel) {
279  break;
282  break;
283  }
284  break;
285  }
286  case vpAfma6::TOOL_GRIPPER: {
287  switch (projModel) {
290  break;
293  break;
294  }
295  break;
296  }
297  case vpAfma6::TOOL_VACUUM: {
298  switch (projModel) {
301  break;
304  break;
305  }
306  break;
307  }
309  switch (projModel) {
312  break;
315  break;
316  }
317  break;
318  }
319  default: {
320  vpERROR_TRACE("This error should not occur!");
321  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
322  // "que les specs de la classe ont ete modifiee, "
323  // "et que le code n'a pas ete mis a jour "
324  // "correctement.");
325  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
326  // "vpAfma6::vpAfma6ToolType, et controlez que "
327  // "tous les cas ont ete pris en compte dans la "
328  // "fonction init(camera).");
329  break;
330  }
331  }
332 
333  this->init(vpAfma6::CONST_AFMA6_FILENAME, filename_eMc);
334 
335 #else // VISP_HAVE_AFMA6_DATA
336 
337  // Use here default values of the robot constant parameters.
338  switch (tool) {
339  case vpAfma6::TOOL_CCMOP: {
340  switch (projModel) {
342  _erc[0] = vpMath::rad(164.35); // rx
343  _erc[1] = vpMath::rad(89.64); // ry
344  _erc[2] = vpMath::rad(-73.05); // rz
345  _etc[0] = 0.0117; // tx
346  _etc[1] = 0.0033; // ty
347  _etc[2] = 0.2272; // tz
348  break;
350  _erc[0] = vpMath::rad(33.54); // rx
351  _erc[1] = vpMath::rad(89.34); // ry
352  _erc[2] = vpMath::rad(57.83); // rz
353  _etc[0] = 0.0373; // tx
354  _etc[1] = 0.0024; // ty
355  _etc[2] = 0.2286; // tz
356  break;
357  }
358  break;
359  }
360  case vpAfma6::TOOL_GRIPPER: {
361  switch (projModel) {
363  _erc[0] = vpMath::rad(88.33); // rx
364  _erc[1] = vpMath::rad(72.07); // ry
365  _erc[2] = vpMath::rad(2.53); // rz
366  _etc[0] = 0.0783; // tx
367  _etc[1] = 0.1234; // ty
368  _etc[2] = 0.1638; // tz
369  break;
371  _erc[0] = vpMath::rad(86.69); // rx
372  _erc[1] = vpMath::rad(71.93); // ry
373  _erc[2] = vpMath::rad(4.17); // rz
374  _etc[0] = 0.1034; // tx
375  _etc[1] = 0.1142; // ty
376  _etc[2] = 0.1642; // tz
377  break;
378  }
379  break;
380  }
381  case vpAfma6::TOOL_VACUUM: {
382  switch (projModel) {
384  _erc[0] = vpMath::rad(90.40); // rx
385  _erc[1] = vpMath::rad(75.11); // ry
386  _erc[2] = vpMath::rad(0.18); // rz
387  _etc[0] = 0.0038; // tx
388  _etc[1] = 0.1281; // ty
389  _etc[2] = 0.1658; // tz
390  break;
392  _erc[0] = vpMath::rad(91.61); // rx
393  _erc[1] = vpMath::rad(76.17); // ry
394  _erc[2] = vpMath::rad(-0.98); // rz
395  _etc[0] = 0.0815; // tx
396  _etc[1] = 0.1162; // ty
397  _etc[2] = 0.1658; // tz
398  break;
399  }
400  break;
401  }
404  switch (projModel) {
407  // set eMc to identity
408  _erc[0] = 0; // rx
409  _erc[1] = 0; // ry
410  _erc[2] = 0; // rz
411  _etc[0] = 0; // tx
412  _etc[1] = 0; // ty
413  _etc[2] = 0; // tz
414  break;
415  }
416  break;
417  }
418  }
419  vpRotationMatrix eRc(_erc);
420  this->_eMc.buildFrom(_etc, eRc);
421 #endif // VISP_HAVE_AFMA6_DATA
422 
423  setToolType(tool);
424  return;
425 }
426 
452 {
454  fMc = get_fMc(q);
455 
456  return fMc;
457 }
458 
531 int vpAfma6::getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest,
532  const bool &verbose) const
533 {
535  double q_[2][6], d[2], t;
536  int ok[2];
537  double cord[6];
538 
539  int nbsol = 0;
540 
541  if (q.getRows() != njoint)
542  q.resize(6);
543 
544  // for(unsigned int i=0;i<3;i++) {
545  // fMe[i][3] = fMc[i][3];
546  // for(int j=0;j<3;j++) {
547  // fMe[i][j] = 0.0;
548  // for (int k=0;k<3;k++) fMe[i][j] += fMc[i][k]*rpi[j][k];
549  // fMe[i][3] -= fMe[i][j]*rpi[j][3];
550  // }
551  // }
552 
553  // std::cout << "\n\nfMc: " << fMc;
554  // std::cout << "\n\neMc: " << _eMc;
555 
556  fMe = fMc * this->_eMc.inverse();
557  // std::cout << "\n\nfMe: " << fMe;
558 
559  if (fMe[2][2] >= .99999f) {
560  vpTRACE("singularity\n");
561  q_[0][4] = q_[1][4] = M_PI / 2.f;
562  t = atan2(fMe[0][0], fMe[0][1]);
563  q_[1][3] = q_[0][3] = q[3];
564  q_[1][5] = q_[0][5] = t - q_[0][3];
565 
566  while ((q_[1][5] + vpMath::rad(2)) >= this->_joint_max[5])
567  /* -> a cause du couplage 4/5 */
568  {
569  q_[1][5] -= vpMath::rad(10);
570  q_[1][3] += vpMath::rad(10);
571  }
572  while (q_[1][5] <= this->_joint_min[5]) {
573  q_[1][5] += vpMath::rad(10);
574  q_[1][3] -= vpMath::rad(10);
575  }
576  } else if (fMe[2][2] <= -.99999) {
577  vpTRACE("singularity\n");
578  q_[0][4] = q_[1][4] = -M_PI / 2;
579  t = atan2(fMe[1][1], fMe[1][0]);
580  q_[1][3] = q_[0][3] = q[3];
581  q_[1][5] = q_[0][5] = q_[0][3] - t;
582  while ((q_[1][5] + vpMath::rad(2)) >= this->_joint_max[5])
583  /* -> a cause du couplage 4/5 */
584  {
585  q_[1][5] -= vpMath::rad(10);
586  q_[1][3] -= vpMath::rad(10);
587  }
588  while (q_[1][5] <= this->_joint_min[5]) {
589  q_[1][5] += vpMath::rad(10);
590  q_[1][3] += vpMath::rad(10);
591  }
592  } else {
593  q_[0][3] = atan2(-fMe[0][2], fMe[1][2]);
594  if (q_[0][3] >= 0.0)
595  q_[1][3] = q_[0][3] - M_PI;
596  else
597  q_[1][3] = q_[0][3] + M_PI;
598 
599  q_[0][4] = asin(fMe[2][2]);
600  if (q_[0][4] >= 0.0)
601  q_[1][4] = M_PI - q_[0][4];
602  else
603  q_[1][4] = -M_PI - q_[0][4];
604 
605  q_[0][5] = atan2(-fMe[2][1], fMe[2][0]);
606  if (q_[0][5] >= 0.0)
607  q_[1][5] = q_[0][5] - M_PI;
608  else
609  q_[1][5] = q_[0][5] + M_PI;
610  }
611  q_[0][0] = fMe[0][3] - this->_long_56 * cos(q_[0][3]);
612  q_[1][0] = fMe[0][3] - this->_long_56 * cos(q_[1][3]);
613  q_[0][1] = fMe[1][3] - this->_long_56 * sin(q_[0][3]);
614  q_[1][1] = fMe[1][3] - this->_long_56 * sin(q_[1][3]);
615  q_[0][2] = q_[1][2] = fMe[2][3];
616 
617  /* prise en compte du couplage axes 5/6 */
618  q_[0][5] += this->_coupl_56 * q_[0][4];
619  q_[1][5] += this->_coupl_56 * q_[1][4];
620 
621  for (int j = 0; j < 2; j++) {
622  ok[j] = 1;
623  // test is position is reachable
624  for (unsigned int i = 0; i < 6; i++) {
625  if (q_[j][i] < this->_joint_min[i] || q_[j][i] > this->_joint_max[i]) {
626  if (verbose) {
627  if (i < 3)
628  std::cout << "Joint " << i << " not in limits: " << this->_joint_min[i] << " < " << q_[j][i] << " < "
629  << this->_joint_max[i] << std::endl;
630  else
631  std::cout << "Joint " << i << " not in limits: " << vpMath::deg(this->_joint_min[i]) << " < "
632  << vpMath::deg(q_[j][i]) << " < " << vpMath::deg(this->_joint_max[i]) << std::endl;
633  }
634  ok[j] = 0;
635  }
636  }
637  }
638  if (ok[0] == 0) {
639  if (ok[1] == 0) {
640  std::cout << "No solution..." << std::endl;
641  nbsol = 0;
642  return nbsol;
643  } else if (ok[1] == 1) {
644  for (unsigned int i = 0; i < 6; i++)
645  cord[i] = q_[1][i];
646  nbsol = 1;
647  }
648  } else {
649  if (ok[1] == 0) {
650  for (unsigned int i = 0; i < 6; i++)
651  cord[i] = q_[0][i];
652  nbsol = 1;
653  } else {
654  nbsol = 2;
655  // vpTRACE("2 solutions\n");
656  for (int j = 0; j < 2; j++) {
657  d[j] = 0.0;
658  for (unsigned int i = 3; i < 6; i++)
659  d[j] += (q_[j][i] - q[i]) * (q_[j][i] - q[i]);
660  }
661  if (nearest == true) {
662  if (d[0] <= d[1])
663  for (unsigned int i = 0; i < 6; i++)
664  cord[i] = q_[0][i];
665  else
666  for (unsigned int i = 0; i < 6; i++)
667  cord[i] = q_[1][i];
668  } else {
669  if (d[0] <= d[1])
670  for (unsigned int i = 0; i < 6; i++)
671  cord[i] = q_[1][i];
672  else
673  for (unsigned int i = 0; i < 6; i++)
674  cord[i] = q_[0][i];
675  }
676  }
677  }
678  for (unsigned int i = 0; i < 6; i++)
679  q[i] = cord[i];
680 
681  return nbsol;
682 }
683 
707 {
709  get_fMc(q, fMc);
710 
711  return fMc;
712 }
713 
734 {
735 
736  // Compute the direct geometric model: fMe = transformation between
737  // fix and end effector frame.
739 
740  get_fMe(q, fMe);
741 
742  fMc = fMe * this->_eMc;
743 
744  return;
745 }
746 
767 {
768  double q0 = q[0]; // meter
769  double q1 = q[1]; // meter
770  double q2 = q[2]; // meter
771 
772  /* Decouplage liaisons 2 et 3. */
773  double q5 = q[5] - this->_coupl_56 * q[4];
774 
775  double c1 = cos(q[3]);
776  double s1 = sin(q[3]);
777  double c2 = cos(q[4]);
778  double s2 = sin(q[4]);
779  double c3 = cos(q5);
780  double s3 = sin(q5);
781 
782  // Compute the direct geometric model: fMe = transformation betwee
783  // fix and end effector frame.
784  fMe[0][0] = s1 * s2 * c3 + c1 * s3;
785  fMe[0][1] = -s1 * s2 * s3 + c1 * c3;
786  fMe[0][2] = -s1 * c2;
787  fMe[0][3] = q0 + this->_long_56 * c1;
788 
789  fMe[1][0] = -c1 * s2 * c3 + s1 * s3;
790  fMe[1][1] = c1 * s2 * s3 + s1 * c3;
791  fMe[1][2] = c1 * c2;
792  fMe[1][3] = q1 + this->_long_56 * s1;
793 
794  fMe[2][0] = c2 * c3;
795  fMe[2][1] = -c2 * s3;
796  fMe[2][2] = s2;
797  fMe[2][3] = q2;
798 
799  fMe[3][0] = 0;
800  fMe[3][1] = 0;
801  fMe[3][2] = 0;
802  fMe[3][3] = 1;
803 
804  // vpCTRACE << "Effector position fMe: " << std::endl << fMe;
805 
806  return;
807 }
808 
819 void vpAfma6::get_cMe(vpHomogeneousMatrix &cMe) const { cMe = this->_eMc.inverse(); }
830 vpHomogeneousMatrix vpAfma6::get_eMc() const { return (this->_eMc); }
831 
842 {
844  get_cMe(cMe);
845 
846  cVe.buildFrom(cMe);
847 
848  return;
849 }
850 
863 void vpAfma6::get_eJe(const vpColVector &q, vpMatrix &eJe) const
864 {
865 
866  eJe.resize(6, 6);
867 
868  double s4, c4, s5, c5, s6, c6;
869 
870  s4 = sin(q[3]);
871  c4 = cos(q[3]);
872  s5 = sin(q[4]);
873  c5 = cos(q[4]);
874  s6 = sin(q[5] - this->_coupl_56 * q[4]);
875  c6 = cos(q[5] - this->_coupl_56 * q[4]);
876 
877  eJe = 0;
878  eJe[0][0] = s4 * s5 * c6 + c4 * s6;
879  eJe[0][1] = -c4 * s5 * c6 + s4 * s6;
880  eJe[0][2] = c5 * c6;
881  eJe[0][3] = -this->_long_56 * s5 * c6;
882 
883  eJe[1][0] = -s4 * s5 * s6 + c4 * c6;
884  eJe[1][1] = c4 * s5 * s6 + s4 * c6;
885  eJe[1][2] = -c5 * s6;
886  eJe[1][3] = this->_long_56 * s5 * s6;
887 
888  eJe[2][0] = -s4 * c5;
889  eJe[2][1] = c4 * c5;
890  eJe[2][2] = s5;
891  eJe[2][3] = this->_long_56 * c5;
892 
893  eJe[3][3] = c5 * c6;
894  eJe[3][4] = s6;
895 
896  eJe[4][3] = -c5 * s6;
897  eJe[4][4] = c6;
898 
899  eJe[5][3] = s5;
900  eJe[5][4] = -this->_coupl_56;
901  eJe[5][5] = 1;
902 
903  return;
904 }
905 
933 void vpAfma6::get_fJe(const vpColVector &q, vpMatrix &fJe) const
934 {
935 
936  fJe.resize(6, 6);
937 
938  // block superieur gauche
939  fJe[0][0] = fJe[1][1] = fJe[2][2] = 1;
940 
941  double s4 = sin(q[3]);
942  double c4 = cos(q[3]);
943 
944  // block superieur droit
945  fJe[0][3] = -this->_long_56 * s4;
946  fJe[1][3] = this->_long_56 * c4;
947 
948  double s5 = sin(q[4]);
949  double c5 = cos(q[4]);
950  // block inferieur droit
951  fJe[3][4] = c4;
952  fJe[3][5] = -s4 * c5;
953  fJe[4][4] = s4;
954  fJe[4][5] = c4 * c5;
955  fJe[5][3] = 1;
956  fJe[5][5] = s5;
957 
958  // coupling between joint 5 and 6
959  fJe[3][4] += this->_coupl_56 * s4 * c5;
960  fJe[4][4] += -this->_coupl_56 * c4 * c5;
961  fJe[5][4] += -this->_coupl_56 * s5;
962 
963  return;
964 }
965 
975 {
976  vpColVector qmin(6);
977  for (unsigned int i = 0; i < 6; i++)
978  qmin[i] = this->_joint_min[i];
979  return qmin;
980 }
981 
991 {
992  vpColVector qmax(6);
993  for (unsigned int i = 0; i < 6; i++)
994  qmax[i] = this->_joint_max[i];
995  return qmax;
996 }
997 
1004 double vpAfma6::getCoupl56() const { return _coupl_56; }
1005 
1012 double vpAfma6::getLong56() const { return _long_56; }
1013 
1024 void vpAfma6::parseConfigFile(const std::string &filename)
1025 {
1026  vpRxyzVector erc; // eMc rotation
1027  vpTranslationVector etc; // eMc translation
1028 
1029  std::ifstream fdconfig(filename.c_str(), std::ios::in);
1030 
1031  if (!fdconfig.is_open()) {
1032  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the config file: %s",
1033  filename.c_str());
1034  }
1035 
1036  std::string line;
1037  int lineNum = 0;
1038  bool get_erc = false;
1039  bool get_etc = false;
1040  int code;
1041 
1042  while (std::getline(fdconfig, line)) {
1043  lineNum++;
1044  if ((line.compare(0, 1, "#") == 0) || line.empty()) { // skip comment or empty line
1045  continue;
1046  }
1047  std::istringstream ss(line);
1048  std::string key;
1049  ss >> key;
1050 
1051  for (code = 0; NULL != opt_Afma6[code]; ++code) {
1052  if (key.compare(opt_Afma6[code]) == 0) {
1053  break;
1054  }
1055  }
1056 
1057  switch (code) {
1058  case 0:
1059  ss >> this->_joint_max[0] >> this->_joint_max[1] >> this->_joint_max[2] >> this->_joint_max[3] >>
1060  this->_joint_max[4] >> this->_joint_max[5];
1061  break;
1062 
1063  case 1:
1064  ss >> this->_joint_min[0] >> this->_joint_min[1] >> this->_joint_min[2] >> this->_joint_min[3] >>
1065  this->_joint_min[4] >> this->_joint_min[5];
1066  break;
1067 
1068  case 2:
1069  ss >> this->_long_56;
1070  break;
1071 
1072  case 3:
1073  ss >> this->_coupl_56;
1074  break;
1075 
1076  case 4:
1077  break; // Nothing to do: camera name
1078 
1079  case 5:
1080  ss >> erc[0] >> erc[1] >> erc[2];
1081 
1082  // Convert rotation from degrees to radians
1083  erc = erc * M_PI / 180.0;
1084  get_erc = true;
1085  break;
1086 
1087  case 6:
1088  ss >> etc[0] >> etc[1] >> etc[2];
1089  get_etc = true;
1090  break;
1091 
1092  default:
1093  throw(vpRobotException(vpRobotException::readingParametersError, "Bad configuration file %s line #%d",
1094  filename.c_str(), lineNum));
1095  }
1096  }
1097 
1098  fdconfig.close();
1099 
1100  // Compute the eMc matrix from the translations and rotations
1101  if (get_etc && get_erc) {
1102  _erc = erc;
1103  _etc = etc;
1104 
1105  vpRotationMatrix eRc(_erc);
1106  this->_eMc.buildFrom(_etc, eRc);
1107  }
1108 }
1109 
1119 {
1120  this->_eMc = eMc;
1121  this->_etc = eMc.getTranslationVector();
1122 
1123  vpRotationMatrix R(eMc);
1124  this->_erc.buildFrom(R);
1125 }
1126 
1189 void vpAfma6::getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width,
1190  const unsigned int &image_height) const
1191 {
1192 #if defined(VISP_HAVE_PUGIXML) && defined(VISP_HAVE_AFMA6_DATA)
1193  vpXmlParserCamera parser;
1194  switch (getToolType()) {
1195  case vpAfma6::TOOL_CCMOP: {
1196  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl
1197  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1199  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1200  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1201  }
1202  break;
1203  }
1204  case vpAfma6::TOOL_GRIPPER: {
1205  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl
1206  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1208  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1209  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1210  }
1211  break;
1212  }
1213  case vpAfma6::TOOL_VACUUM: {
1214  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl
1215  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1217  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1218  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1219  }
1220  break;
1221  }
1223  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
1224  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1226  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1227  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1228  }
1229  break;
1230  }
1231  default: {
1232  vpERROR_TRACE("This error should not occur!");
1233  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
1234  // "que les specs de la classe ont ete modifiee, "
1235  // "et que le code n'a pas ete mis a jour "
1236  // "correctement.");
1237  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
1238  // "vpAfma6::vpAfma6ToolType, et controlez que "
1239  // "tous les cas ont ete pris en compte dans la "
1240  // "fonction init(camera).");
1241  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1242  }
1243  }
1244 #else
1245  // Set default parameters
1246  switch (getToolType()) {
1247  case vpAfma6::TOOL_CCMOP: {
1248  // Set default intrinsic camera parameters for 640x480 images
1249  if (image_width == 640 && image_height == 480) {
1250  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\""
1251  << std::endl;
1252  switch (this->projModel) {
1254  cam.initPersProjWithoutDistortion(1108.0, 1110.0, 314.5, 243.2);
1255  break;
1257  cam.initPersProjWithDistortion(1090.6, 1090.0, 310.1, 260.8, -0.2114, 0.2217);
1258  break;
1259  }
1260  } else {
1261  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1262  "resolution");
1263  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1264  }
1265  break;
1266  }
1267  case vpAfma6::TOOL_GRIPPER: {
1268  // Set default intrinsic camera parameters for 640x480 images
1269  if (image_width == 640 && image_height == 480) {
1270  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\""
1271  << std::endl;
1272  switch (this->projModel) {
1274  cam.initPersProjWithoutDistortion(850.9, 853.0, 311.1, 243.6);
1275  break;
1277  cam.initPersProjWithDistortion(837.0, 837.5, 308.7, 251.6, -0.1455, 0.1511);
1278  break;
1279  }
1280  } else {
1281  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1282  "resolution");
1283  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1284  }
1285  break;
1286  }
1287  case vpAfma6::TOOL_VACUUM: {
1288  // Set default intrinsic camera parameters for 640x480 images
1289  if (image_width == 640 && image_height == 480) {
1290  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\""
1291  << std::endl;
1292  switch (this->projModel) {
1294  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1295  break;
1297  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1298  break;
1299  }
1300  } else {
1301  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1302  "resolution");
1303  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1304  }
1305  break;
1306  }
1308  // Set default intrinsic camera parameters for 640x480 images
1309  if (image_width == 640 && image_height == 480) {
1310  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\""
1311  << std::endl;
1312  switch (this->projModel) {
1314  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1315  break;
1317  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1318  break;
1319  }
1320  } else {
1321  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1322  "resolution");
1323  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1324  }
1325  break;
1326  }
1327  default:
1328  vpERROR_TRACE("This error should not occur!");
1329  break;
1330  }
1331 #endif
1332  return;
1333 }
1334 
1378 {
1379  getCameraParameters(cam, I.getWidth(), I.getHeight());
1380 }
1425 {
1426  getCameraParameters(cam, I.getWidth(), I.getHeight());
1427 }
1428 
1438 VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAfma6 &afma6)
1439 {
1440  vpRotationMatrix eRc;
1441  afma6._eMc.extract(eRc);
1442  vpRxyzVector rxyz(eRc);
1443 
1444  os << "Joint Max:" << std::endl
1445  << "\t" << afma6._joint_max[0] << "\t" << afma6._joint_max[1] << "\t" << afma6._joint_max[2] << "\t"
1446  << afma6._joint_max[3] << "\t" << afma6._joint_max[4] << "\t" << afma6._joint_max[5] << "\t" << std::endl
1447 
1448  << "Joint Min: " << std::endl
1449  << "\t" << afma6._joint_min[0] << "\t" << afma6._joint_min[1] << "\t" << afma6._joint_min[2] << "\t"
1450  << afma6._joint_min[3] << "\t" << afma6._joint_min[4] << "\t" << afma6._joint_min[5] << "\t" << std::endl
1451 
1452  << "Long 5-6: " << std::endl
1453  << "\t" << afma6._long_56 << "\t" << std::endl
1454 
1455  << "Coupling 5-6:" << std::endl
1456  << "\t" << afma6._coupl_56 << "\t" << std::endl
1457 
1458  << "eMc: " << std::endl
1459  << "\tTranslation (m): " << afma6._eMc[0][3] << " " << afma6._eMc[1][3] << " " << afma6._eMc[2][3] << "\t"
1460  << std::endl
1461  << "\tRotation Rxyz (rad) : " << rxyz[0] << " " << rxyz[1] << " " << rxyz[2] << "\t" << std::endl
1462  << "\tRotation Rxyz (deg) : " << vpMath::deg(rxyz[0]) << " " << vpMath::deg(rxyz[1]) << " " << vpMath::deg(rxyz[2])
1463  << "\t" << std::endl;
1464 
1465  return os;
1466 }
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:92
Modelisation of Irisa&#39;s gantry robot named Afma6.
Definition: vpAfma6.h:78
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:164
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpAfma6.cpp:1189
vpRxyzVector _erc
Definition: vpAfma6.h:198
vpTranslationVector _etc
Definition: vpAfma6.h:197
static const unsigned int njoint
Number of joint.
Definition: vpAfma6.h:185
static const std::string CONST_AFMA6_FILENAME
Definition: vpAfma6.h:85
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition: vpArray2D.h:305
Error that can be emited by the vpRobot class and its derivates.
static const std::string CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:88
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpColVector getJointMax() const
Definition: vpAfma6.cpp:990
#define vpERROR_TRACE
Definition: vpDebug.h:393
void parseConfigFile(const std::string &filename)
Definition: vpAfma6.cpp:1024
static const std::string CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:87
double _coupl_56
Definition: vpAfma6.h:192
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition: vpAfma6.cpp:531
static const std::string CONST_CAMERA_AFMA6_FILENAME
Definition: vpAfma6.h:94
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpAfma6.cpp:841
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:118
unsigned int getRows() const
Definition: vpArray2D.h:289
vpHomogeneousMatrix inverse() const
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpAfma6.h:206
vpAfma6ToolType getToolType() const
Get the current tool type.
Definition: vpAfma6.h:160
void extract(vpRotationMatrix &R) const
XML parser to load and save intrinsic camera parameters.
void initPersProjWithDistortion(double px, double py, double u0, double v0, double kud, double kdu)
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:706
friend VISP_EXPORT std::ostream & operator<<(std::ostream &os, const vpAfma6 &afma6)
Definition: vpAfma6.cpp:1438
double getLong56() const
Definition: vpAfma6.cpp:1012
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition: vpAfma6.h:185
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:93
static const char *const CONST_GRIPPER_CAMERA_NAME
Definition: vpAfma6.h:105
Implementation of a rotation matrix and operations on such kind of matrices.
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpAfma6.h:127
vpHomogeneousMatrix get_eMc() const
Definition: vpAfma6.cpp:830
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static const std::string CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:90
#define vpTRACE
Definition: vpDebug.h:416
static const std::string CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:91
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpAfma6.cpp:863
Generic class defining intrinsic camera parameters.
vpColVector getJointMin() const
Definition: vpAfma6.cpp:974
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Definition: vpAfma6.cpp:451
vpAfma6()
Definition: vpAfma6.cpp:114
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:933
static double rad(double deg)
Definition: vpMath.h:108
static const std::string CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:86
int parse(vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, unsigned int image_width=0, unsigned int image_height=0)
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpAfma6.cpp:766
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
Definition: vpAfma6.cpp:1118
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:310
vpTranslationVector getTranslationVector() const
double _long_56
Definition: vpAfma6.h:193
static double deg(double rad)
Definition: vpMath.h:101
unsigned int getHeight() const
Definition: vpImage.h:186
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:819
vpHomogeneousMatrix _eMc
Definition: vpAfma6.h:200
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
void init(void)
Definition: vpAfma6.cpp:153
double _joint_max[6]
Definition: vpAfma6.h:194
static const char *const CONST_CCMOP_CAMERA_NAME
Definition: vpAfma6.h:100
unsigned int getWidth() const
Definition: vpImage.h:244
static const std::string CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:89
static const char *const CONST_VACUUM_CAMERA_NAME
Definition: vpAfma6.h:110
Class that consider the case of a translation vector.
double getCoupl56() const
Definition: vpAfma6.cpp:1004
double _joint_min[6]
Definition: vpAfma6.h:195
static const char *const CONST_GENERIC_CAMERA_NAME
Definition: vpAfma6.h:115