Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpAfma6.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for the Irisa's Afma6 robot.
33  *
34 *****************************************************************************/
35 
44 #include <iostream>
45 #include <sstream>
46 
47 #include <visp3/core/vpCameraParameters.h>
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpRotationMatrix.h>
50 #include <visp3/core/vpRxyzVector.h>
51 #include <visp3/core/vpTranslationVector.h>
52 #include <visp3/core/vpVelocityTwistMatrix.h>
53 #include <visp3/core/vpXmlParserCamera.h>
54 #include <visp3/robot/vpAfma6.h>
55 #include <visp3/robot/vpRobotException.h>
56 
57 /* ----------------------------------------------------------------------- */
58 /* --- STATIC ------------------------------------------------------------ */
59 /* ---------------------------------------------------------------------- */
60 
62 static const char *opt_Afma6[] = { "JOINT_MAX", "JOINT_MIN", "LONG_56", "COUPL_56",
63  "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr };
64 
65 #ifdef VISP_HAVE_AFMA6_DATA
66 const std::string vpAfma6::CONST_AFMA6_FILENAME =
67 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_Afma6.cnf");
68 
70 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_without_distortion_Afma6.cnf");
71 
73 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_with_distortion_Afma6.cnf");
74 
76 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_without_distortion_Afma6.cnf");
77 
79 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_with_distortion_Afma6.cnf");
80 
82 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_without_distortion_Afma6.cnf");
83 
85 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_with_distortion_Afma6.cnf");
86 
88 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_without_distortion_Afma6.cnf");
89 
91 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_with_distortion_Afma6.cnf");
92 
94 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_Intel_D435_without_distortion_Afma6.cnf");
95 
97 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_Intel_D435_with_distortion_Afma6.cnf");
98 
99 const std::string vpAfma6::CONST_CAMERA_AFMA6_FILENAME =
100 std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_camera_Afma6.xml");
101 
102 #endif // VISP_HAVE_AFMA6_DATA
103 
104 const char *const vpAfma6::CONST_CCMOP_CAMERA_NAME = "Dragonfly2-8mm-ccmop";
105 const char *const vpAfma6::CONST_GRIPPER_CAMERA_NAME = "Dragonfly2-6mm-gripper";
106 const char *const vpAfma6::CONST_VACUUM_CAMERA_NAME = "Dragonfly2-6mm-vacuum";
107 const char *const vpAfma6::CONST_GENERIC_CAMERA_NAME = "Generic-camera";
108 const char *const vpAfma6::CONST_INTEL_D435_CAMERA_NAME = "Intel-D435";
109 
111 
112 const unsigned int vpAfma6::njoint = 6;
113 
120  : _coupl_56(0), _long_56(0), _etc(), _erc(), _eMc(), tool_current(vpAfma6::defaultTool),
121  projModel(vpCameraParameters::perspectiveProjWithoutDistortion)
122 {
123  // Set the default parameters in case of the config files are not available.
124 
125  //
126  // Geometric model constant parameters
127  //
128  // coupling between join 5 and 6
129  this->_coupl_56 = 0.009091;
130  // distance between join 5 and 6
131  this->_long_56 = -0.06924;
132  // Camera extrinsic parameters: effector to camera frame
133  this->_eMc.eye(); // Default values are initialized ...
134  // ... in init (vpAfma6::vpAfma6ToolType tool,
135  // vpCameraParameters::vpCameraParametersProjType projModel)
136  // Maximal value of the joints
137  this->_joint_max[0] = 0.7001;
138  this->_joint_max[1] = 0.5201;
139  this->_joint_max[2] = 0.4601;
140  this->_joint_max[3] = 2.7301;
141  this->_joint_max[4] = 2.4801;
142  this->_joint_max[5] = 1.5901;
143  // Minimal value of the joints
144  this->_joint_min[0] = -0.6501;
145  this->_joint_min[1] = -0.6001;
146  this->_joint_min[2] = -0.5001;
147  this->_joint_min[3] = -2.7301;
148  this->_joint_min[4] = -0.1001;
149  this->_joint_min[5] = -1.5901;
150 
151  init();
152 }
153 
158 void vpAfma6::init(void)
159 {
160  this->init(vpAfma6::defaultTool);
161  return;
162 }
163 
176 void vpAfma6::init(const std::string &camera_extrinsic_parameters, const std::string &camera_intrinsic_parameters)
177 {
178  this->parseConfigFile(camera_extrinsic_parameters);
179 
180  this->parseConfigFile(camera_intrinsic_parameters);
181 }
182 
213 void vpAfma6::init(vpAfma6::vpAfma6ToolType tool, const std::string &filename)
214 {
215  this->setToolType(tool);
216  this->parseConfigFile(filename.c_str());
217 }
218 
228 void vpAfma6::init(const std::string &camera_extrinsic_parameters)
229 {
230  this->parseConfigFile(camera_extrinsic_parameters);
231 }
232 
249 {
250  this->setToolType(tool);
251  this->set_eMc(eMc);
252 }
253 
272 {
273 
274  this->projModel = proj_model;
275 
276 #ifdef VISP_HAVE_AFMA6_DATA
277  // Read the robot parameters from files
278  std::string filename_eMc;
279  switch (tool) {
280  case vpAfma6::TOOL_CCMOP: {
281  switch (projModel) {
284  break;
287  break;
290  "Feature TOOL_CCMOP is not implemented for Kannala-Brandt projection model yet.");
291  break;
292  }
293  break;
294  }
295  case vpAfma6::TOOL_GRIPPER: {
296  switch (projModel) {
299  break;
302  break;
305  "Feature TOOL_GRIPPER is not implemented for Kannala-Brandt projection model yet.");
306  break;
307  }
308  break;
309  }
310  case vpAfma6::TOOL_VACUUM: {
311  switch (projModel) {
314  break;
317  break;
320  "Feature TOOL_VACUUM is not implemented for Kannala-Brandt projection model yet.");
321  break;
322  }
323  break;
324  }
326  switch (projModel) {
329  break;
332  break;
335  "Feature TOOL_INTEL_D435_CAMERA is not implemented for Kannala-Brandt projection model yet.");
336  break;
337  }
338  break;
339  }
341  switch (projModel) {
344  break;
347  break;
350  "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
351  break;
352  }
353  break;
354  }
355  default: {
356  vpERROR_TRACE("This error should not occur!");
357  break;
358  }
359  }
360 
361  this->init(vpAfma6::CONST_AFMA6_FILENAME, filename_eMc);
362 
363 #else // VISP_HAVE_AFMA6_DATA
364 
365  // Use here default values of the robot constant parameters.
366  switch (tool) {
367  case vpAfma6::TOOL_CCMOP: {
368  switch (projModel) {
370  _erc[0] = vpMath::rad(164.35); // rx
371  _erc[1] = vpMath::rad(89.64); // ry
372  _erc[2] = vpMath::rad(-73.05); // rz
373  _etc[0] = 0.0117; // tx
374  _etc[1] = 0.0033; // ty
375  _etc[2] = 0.2272; // tz
376  break;
378  _erc[0] = vpMath::rad(33.54); // rx
379  _erc[1] = vpMath::rad(89.34); // ry
380  _erc[2] = vpMath::rad(57.83); // rz
381  _etc[0] = 0.0373; // tx
382  _etc[1] = 0.0024; // ty
383  _etc[2] = 0.2286; // tz
384  break;
387  "Feature TOOL_CCMOP is not implemented for Kannala-Brandt projection model yet.");
388  break;
389  }
390  break;
391  }
392  case vpAfma6::TOOL_GRIPPER: {
393  switch (projModel) {
395  _erc[0] = vpMath::rad(88.33); // rx
396  _erc[1] = vpMath::rad(72.07); // ry
397  _erc[2] = vpMath::rad(2.53); // rz
398  _etc[0] = 0.0783; // tx
399  _etc[1] = 0.1234; // ty
400  _etc[2] = 0.1638; // tz
401  break;
403  _erc[0] = vpMath::rad(86.69); // rx
404  _erc[1] = vpMath::rad(71.93); // ry
405  _erc[2] = vpMath::rad(4.17); // rz
406  _etc[0] = 0.1034; // tx
407  _etc[1] = 0.1142; // ty
408  _etc[2] = 0.1642; // tz
409  break;
412  "Feature TOOL_GRIPPER is not implemented for Kannala-Brandt projection model yet.");
413  break;
414  }
415  break;
416  }
417  case vpAfma6::TOOL_VACUUM: {
418  switch (projModel) {
420  _erc[0] = vpMath::rad(90.40); // rx
421  _erc[1] = vpMath::rad(75.11); // ry
422  _erc[2] = vpMath::rad(0.18); // rz
423  _etc[0] = 0.0038; // tx
424  _etc[1] = 0.1281; // ty
425  _etc[2] = 0.1658; // tz
426  break;
428  _erc[0] = vpMath::rad(91.61); // rx
429  _erc[1] = vpMath::rad(76.17); // ry
430  _erc[2] = vpMath::rad(-0.98); // rz
431  _etc[0] = 0.0815; // tx
432  _etc[1] = 0.1162; // ty
433  _etc[2] = 0.1658; // tz
434  break;
437  "Feature TOOL_VACUUM is not implemented for Kannala-Brandt projection model yet.");
438  break;
439  }
440  break;
441  }
443  switch (projModel) {
445  _erc[0] = vpMath::rad(-71.41); // rx
446  _erc[1] = vpMath::rad(89.49); // ry
447  _erc[2] = vpMath::rad(162.07); // rz
448  _etc[0] = 0.0038; // tx
449  _etc[1] = 0.1281; // ty
450  _etc[2] = 0.1658; // tz
451  break;
453  _erc[0] = vpMath::rad(-52.79); // rx
454  _erc[1] = vpMath::rad(89.55); // ry
455  _erc[2] = vpMath::rad(143.34); // rz
456  _etc[0] = 0.0693; // tx
457  _etc[1] = -0.0297; // ty
458  _etc[2] = 0.1357; // tz
459  break;
462  "Feature TOOL_INTEL_D435_CAMERA is not implemented for Kannala-Brandt projection model yet.");
463  break;
464  }
465  break;
466  }
469  switch (projModel) {
472  // set eMc to identity
473  _erc[0] = 0; // rx
474  _erc[1] = 0; // ry
475  _erc[2] = 0; // rz
476  _etc[0] = 0; // tx
477  _etc[1] = 0; // ty
478  _etc[2] = 0; // tz
479  break;
482  "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
483  break;
484  }
485  break;
486  }
487  }
488  vpRotationMatrix eRc(_erc);
489  this->_eMc.build(_etc, eRc);
490 #endif // VISP_HAVE_AFMA6_DATA
491 
492  setToolType(tool);
493  return;
494 }
495 
521 {
523  fMc = get_fMc(q);
524 
525  return fMc;
526 }
527 
604 int vpAfma6::getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest,
605  const bool &verbose) const
606 {
608  double q_[2][6], d[2], t;
609  int ok[2];
610  double cord[6];
611 
612  int nbsol = 0;
613 
614  if (q.getRows() != njoint)
615  q.resize(6);
616 
617  // for(unsigned int i=0;i<3;i++) {
618  // fMe[i][3] = fMc[i][3];
619  // for(int j=0;j<3;j++) {
620  // fMe[i][j] = 0.0;
621  // for (int k=0;k<3;k++) fMe[i][j] += fMc[i][k]*rpi[j][k];
622  // fMe[i][3] -= fMe[i][j]*rpi[j][3];
623  // }
624  // }
625 
626  // std::cout << "\n\nfMc: " << fMc;
627  // std::cout << "\n\neMc: " << _eMc;
628 
629  fMe = fMc * this->_eMc.inverse();
630  // std::cout << "\n\nfMe: " << fMe;
631 
632  if (fMe[2][2] >= .99999f) {
633  vpTRACE("singularity\n");
634  q_[0][4] = q_[1][4] = M_PI / 2.f;
635  t = atan2(fMe[0][0], fMe[0][1]);
636  q_[1][3] = q_[0][3] = q[3];
637  q_[1][5] = q_[0][5] = t - q_[0][3];
638 
639  while ((q_[1][5] + vpMath::rad(2)) >= this->_joint_max[5])
640  /* -> a cause du couplage 4/5 */
641  {
642  q_[1][5] -= vpMath::rad(10);
643  q_[1][3] += vpMath::rad(10);
644  }
645  while (q_[1][5] <= this->_joint_min[5]) {
646  q_[1][5] += vpMath::rad(10);
647  q_[1][3] -= vpMath::rad(10);
648  }
649  }
650  else if (fMe[2][2] <= -.99999) {
651  vpTRACE("singularity\n");
652  q_[0][4] = q_[1][4] = -M_PI / 2;
653  t = atan2(fMe[1][1], fMe[1][0]);
654  q_[1][3] = q_[0][3] = q[3];
655  q_[1][5] = q_[0][5] = q_[0][3] - t;
656  while ((q_[1][5] + vpMath::rad(2)) >= this->_joint_max[5])
657  /* -> a cause du couplage 4/5 */
658  {
659  q_[1][5] -= vpMath::rad(10);
660  q_[1][3] -= vpMath::rad(10);
661  }
662  while (q_[1][5] <= this->_joint_min[5]) {
663  q_[1][5] += vpMath::rad(10);
664  q_[1][3] += vpMath::rad(10);
665  }
666  }
667  else {
668  q_[0][3] = atan2(-fMe[0][2], fMe[1][2]);
669  if (q_[0][3] >= 0.0)
670  q_[1][3] = q_[0][3] - M_PI;
671  else
672  q_[1][3] = q_[0][3] + M_PI;
673 
674  q_[0][4] = asin(fMe[2][2]);
675  if (q_[0][4] >= 0.0)
676  q_[1][4] = M_PI - q_[0][4];
677  else
678  q_[1][4] = -M_PI - q_[0][4];
679 
680  q_[0][5] = atan2(-fMe[2][1], fMe[2][0]);
681  if (q_[0][5] >= 0.0)
682  q_[1][5] = q_[0][5] - M_PI;
683  else
684  q_[1][5] = q_[0][5] + M_PI;
685  }
686  q_[0][0] = fMe[0][3] - this->_long_56 * cos(q_[0][3]);
687  q_[1][0] = fMe[0][3] - this->_long_56 * cos(q_[1][3]);
688  q_[0][1] = fMe[1][3] - this->_long_56 * sin(q_[0][3]);
689  q_[1][1] = fMe[1][3] - this->_long_56 * sin(q_[1][3]);
690  q_[0][2] = q_[1][2] = fMe[2][3];
691 
692  /* prise en compte du couplage axes 5/6 */
693  q_[0][5] += this->_coupl_56 * q_[0][4];
694  q_[1][5] += this->_coupl_56 * q_[1][4];
695 
696  for (int j = 0; j < 2; j++) {
697  ok[j] = 1;
698  // test is position is reachable
699  for (unsigned int i = 0; i < 6; i++) {
700  if (q_[j][i] < this->_joint_min[i] || q_[j][i] > this->_joint_max[i]) {
701  if (verbose) {
702  if (i < 3)
703  std::cout << "Joint " << i << " not in limits: " << this->_joint_min[i] << " < " << q_[j][i] << " < "
704  << this->_joint_max[i] << std::endl;
705  else
706  std::cout << "Joint " << i << " not in limits: " << vpMath::deg(this->_joint_min[i]) << " < "
707  << vpMath::deg(q_[j][i]) << " < " << vpMath::deg(this->_joint_max[i]) << std::endl;
708  }
709  ok[j] = 0;
710  }
711  }
712  }
713  if (ok[0] == 0) {
714  if (ok[1] == 0) {
715  std::cout << "No solution..." << std::endl;
716  nbsol = 0;
717  return nbsol;
718  }
719  else if (ok[1] == 1) {
720  for (unsigned int i = 0; i < 6; i++)
721  cord[i] = q_[1][i];
722  nbsol = 1;
723  }
724  }
725  else {
726  if (ok[1] == 0) {
727  for (unsigned int i = 0; i < 6; i++)
728  cord[i] = q_[0][i];
729  nbsol = 1;
730  }
731  else {
732  nbsol = 2;
733  // vpTRACE("2 solutions\n");
734  for (int j = 0; j < 2; j++) {
735  d[j] = 0.0;
736  for (unsigned int i = 3; i < 6; i++)
737  d[j] += (q_[j][i] - q[i]) * (q_[j][i] - q[i]);
738  }
739  if (nearest == true) {
740  if (d[0] <= d[1])
741  for (unsigned int i = 0; i < 6; i++)
742  cord[i] = q_[0][i];
743  else
744  for (unsigned int i = 0; i < 6; i++)
745  cord[i] = q_[1][i];
746  }
747  else {
748  if (d[0] <= d[1])
749  for (unsigned int i = 0; i < 6; i++)
750  cord[i] = q_[1][i];
751  else
752  for (unsigned int i = 0; i < 6; i++)
753  cord[i] = q_[0][i];
754  }
755  }
756  }
757  for (unsigned int i = 0; i < 6; i++)
758  q[i] = cord[i];
759 
760  return nbsol;
761 }
762 
786 {
788  get_fMc(q, fMc);
789 
790  return fMc;
791 }
792 
813 {
814 
815  // Compute the direct geometric model: fMe = transformation between
816  // fix and end effector frame.
818 
819  get_fMe(q, fMe);
820 
821  fMc = fMe * this->_eMc;
822 
823  return;
824 }
825 
846 {
847  double q0 = q[0]; // meter
848  double q1 = q[1]; // meter
849  double q2 = q[2]; // meter
850 
851  /* Decouplage liaisons 2 et 3. */
852  double q5 = q[5] - this->_coupl_56 * q[4];
853 
854  double c1 = cos(q[3]);
855  double s1 = sin(q[3]);
856  double c2 = cos(q[4]);
857  double s2 = sin(q[4]);
858  double c3 = cos(q5);
859  double s3 = sin(q5);
860 
861  // Compute the direct geometric model: fMe = transformation betwee
862  // fix and end effector frame.
863  fMe[0][0] = s1 * s2 * c3 + c1 * s3;
864  fMe[0][1] = -s1 * s2 * s3 + c1 * c3;
865  fMe[0][2] = -s1 * c2;
866  fMe[0][3] = q0 + this->_long_56 * c1;
867 
868  fMe[1][0] = -c1 * s2 * c3 + s1 * s3;
869  fMe[1][1] = c1 * s2 * s3 + s1 * c3;
870  fMe[1][2] = c1 * c2;
871  fMe[1][3] = q1 + this->_long_56 * s1;
872 
873  fMe[2][0] = c2 * c3;
874  fMe[2][1] = -c2 * s3;
875  fMe[2][2] = s2;
876  fMe[2][3] = q2;
877 
878  fMe[3][0] = 0;
879  fMe[3][1] = 0;
880  fMe[3][2] = 0;
881  fMe[3][3] = 1;
882 
883  // vpCTRACE << "Effector position fMe: " << std::endl << fMe;
884 
885  return;
886 }
887 
898 void vpAfma6::get_cMe(vpHomogeneousMatrix &cMe) const { cMe = this->_eMc.inverse(); }
909 vpHomogeneousMatrix vpAfma6::get_eMc() const { return (this->_eMc); }
910 
921 {
923  get_cMe(cMe);
924 
925  cVe.build(cMe);
926 
927  return;
928 }
929 
942 void vpAfma6::get_eJe(const vpColVector &q, vpMatrix &eJe) const
943 {
944 
945  eJe.resize(6, 6);
946 
947  double s4, c4, s5, c5, s6, c6;
948 
949  s4 = sin(q[3]);
950  c4 = cos(q[3]);
951  s5 = sin(q[4]);
952  c5 = cos(q[4]);
953  s6 = sin(q[5] - this->_coupl_56 * q[4]);
954  c6 = cos(q[5] - this->_coupl_56 * q[4]);
955 
956  eJe = 0;
957  eJe[0][0] = s4 * s5 * c6 + c4 * s6;
958  eJe[0][1] = -c4 * s5 * c6 + s4 * s6;
959  eJe[0][2] = c5 * c6;
960  eJe[0][3] = -this->_long_56 * s5 * c6;
961 
962  eJe[1][0] = -s4 * s5 * s6 + c4 * c6;
963  eJe[1][1] = c4 * s5 * s6 + s4 * c6;
964  eJe[1][2] = -c5 * s6;
965  eJe[1][3] = this->_long_56 * s5 * s6;
966 
967  eJe[2][0] = -s4 * c5;
968  eJe[2][1] = c4 * c5;
969  eJe[2][2] = s5;
970  eJe[2][3] = this->_long_56 * c5;
971 
972  eJe[3][3] = c5 * c6;
973  eJe[3][4] = s6;
974 
975  eJe[4][3] = -c5 * s6;
976  eJe[4][4] = c6;
977 
978  eJe[5][3] = s5;
979  eJe[5][4] = -this->_coupl_56;
980  eJe[5][5] = 1;
981 
982  return;
983 }
984 
1012 void vpAfma6::get_fJe(const vpColVector &q, vpMatrix &fJe) const
1013 {
1014 
1015  fJe.resize(6, 6);
1016 
1017  // block superieur gauche
1018  fJe[0][0] = fJe[1][1] = fJe[2][2] = 1;
1019 
1020  double s4 = sin(q[3]);
1021  double c4 = cos(q[3]);
1022 
1023  // block superieur droit
1024  fJe[0][3] = -this->_long_56 * s4;
1025  fJe[1][3] = this->_long_56 * c4;
1026 
1027  double s5 = sin(q[4]);
1028  double c5 = cos(q[4]);
1029  // block inferieur droit
1030  fJe[3][4] = c4;
1031  fJe[3][5] = -s4 * c5;
1032  fJe[4][4] = s4;
1033  fJe[4][5] = c4 * c5;
1034  fJe[5][3] = 1;
1035  fJe[5][5] = s5;
1036 
1037  // coupling between joint 5 and 6
1038  fJe[3][4] += this->_coupl_56 * s4 * c5;
1039  fJe[4][4] += -this->_coupl_56 * c4 * c5;
1040  fJe[5][4] += -this->_coupl_56 * s5;
1041 
1042  return;
1043 }
1044 
1054 {
1055  vpColVector qmin(6);
1056  for (unsigned int i = 0; i < 6; i++)
1057  qmin[i] = this->_joint_min[i];
1058  return qmin;
1059 }
1060 
1070 {
1071  vpColVector qmax(6);
1072  for (unsigned int i = 0; i < 6; i++)
1073  qmax[i] = this->_joint_max[i];
1074  return qmax;
1075 }
1076 
1083 double vpAfma6::getCoupl56() const { return _coupl_56; }
1084 
1091 double vpAfma6::getLong56() const { return _long_56; }
1092 
1103 void vpAfma6::parseConfigFile(const std::string &filename)
1104 {
1105  vpRxyzVector erc; // eMc rotation
1106  vpTranslationVector etc; // eMc translation
1107 
1108  std::ifstream fdconfig(filename.c_str(), std::ios::in);
1109 
1110  if (!fdconfig.is_open()) {
1111  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the config file: %s",
1112  filename.c_str());
1113  }
1114 
1115  std::string line;
1116  int lineNum = 0;
1117  bool get_erc = false;
1118  bool get_etc = false;
1119  int code;
1120 
1121  while (std::getline(fdconfig, line)) {
1122  lineNum++;
1123  if ((line.compare(0, 1, "#") == 0) || line.empty()) { // skip comment or empty line
1124  continue;
1125  }
1126  std::istringstream ss(line);
1127  std::string key;
1128  ss >> key;
1129 
1130  for (code = 0; nullptr != opt_Afma6[code]; ++code) {
1131  if (key.compare(opt_Afma6[code]) == 0) {
1132  break;
1133  }
1134  }
1135 
1136  switch (code) {
1137  case 0:
1138  ss >> this->_joint_max[0] >> this->_joint_max[1] >> this->_joint_max[2] >> this->_joint_max[3] >>
1139  this->_joint_max[4] >> this->_joint_max[5];
1140  break;
1141 
1142  case 1:
1143  ss >> this->_joint_min[0] >> this->_joint_min[1] >> this->_joint_min[2] >> this->_joint_min[3] >>
1144  this->_joint_min[4] >> this->_joint_min[5];
1145  break;
1146 
1147  case 2:
1148  ss >> this->_long_56;
1149  break;
1150 
1151  case 3:
1152  ss >> this->_coupl_56;
1153  break;
1154 
1155  case 4:
1156  break; // Nothing to do: camera name
1157 
1158  case 5:
1159  ss >> erc[0] >> erc[1] >> erc[2];
1160 
1161  // Convert rotation from degrees to radians
1162  erc = erc * M_PI / 180.0;
1163  get_erc = true;
1164  break;
1165 
1166  case 6:
1167  ss >> etc[0] >> etc[1] >> etc[2];
1168  get_etc = true;
1169  break;
1170 
1171  default:
1172  throw(vpRobotException(vpRobotException::readingParametersError, "Bad configuration file %s line #%d",
1173  filename.c_str(), lineNum));
1174  }
1175  }
1176 
1177  fdconfig.close();
1178 
1179  // Compute the eMc matrix from the translations and rotations
1180  if (get_etc && get_erc) {
1181  _erc = erc;
1182  _etc = etc;
1183 
1184  vpRotationMatrix eRc(_erc);
1185  this->_eMc.build(_etc, eRc);
1186  }
1187 }
1188 
1198 {
1199  this->_eMc = eMc;
1200  this->_etc = eMc.getTranslationVector();
1201 
1202  vpRotationMatrix R(eMc);
1203  this->_erc.build(R);
1204 }
1205 
1270 void vpAfma6::getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width,
1271  const unsigned int &image_height) const
1272 {
1273 #if defined(VISP_HAVE_AFMA6_DATA) && defined(VISP_HAVE_PUGIXML)
1274  vpXmlParserCamera parser;
1275  switch (getToolType()) {
1276  case vpAfma6::TOOL_CCMOP: {
1277  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl
1278  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1280  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1281  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1282  }
1283  break;
1284  }
1285  case vpAfma6::TOOL_GRIPPER: {
1286  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl
1287  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1289  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1290  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1291  }
1292  break;
1293  }
1294  case vpAfma6::TOOL_VACUUM: {
1295  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl
1296  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1298  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1299  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1300  }
1301  break;
1302  }
1304  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_INTEL_D435_CAMERA_NAME << "\"" << std::endl
1305  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1307  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1308  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1309  }
1310  break;
1311  }
1313  std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
1314  << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1316  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1317  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1318  }
1319  break;
1320  }
1321  default: {
1322  vpERROR_TRACE("This error should not occur!");
1323  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
1324  // "que les specs de la classe ont ete modifiee, "
1325  // "et que le code n'a pas ete mis a jour "
1326  // "correctement.");
1327  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
1328  // "vpAfma6::vpAfma6ToolType, et controlez que "
1329  // "tous les cas ont ete pris en compte dans la "
1330  // "fonction init(camera).");
1331  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1332  }
1333  }
1334 #else
1335  // Set default parameters
1336  switch (getToolType()) {
1337  case vpAfma6::TOOL_CCMOP: {
1338  // Set default intrinsic camera parameters for 640x480 images
1339  if (image_width == 640 && image_height == 480) {
1340  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\""
1341  << std::endl;
1342  switch (this->projModel) {
1344  cam.initPersProjWithoutDistortion(1108.0, 1110.0, 314.5, 243.2);
1345  break;
1347  cam.initPersProjWithDistortion(1090.6, 1090.0, 310.1, 260.8, -0.2114, 0.2217);
1348  break;
1351  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1352  break;
1353  }
1354  }
1355  else {
1356  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1357  "resolution");
1358  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1359  }
1360  break;
1361  }
1362  case vpAfma6::TOOL_GRIPPER: {
1363  // Set default intrinsic camera parameters for 640x480 images
1364  if (image_width == 640 && image_height == 480) {
1365  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\""
1366  << std::endl;
1367  switch (this->projModel) {
1369  cam.initPersProjWithoutDistortion(850.9, 853.0, 311.1, 243.6);
1370  break;
1372  cam.initPersProjWithDistortion(837.0, 837.5, 308.7, 251.6, -0.1455, 0.1511);
1373  break;
1376  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1377  break;
1378  }
1379  }
1380  else {
1381  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1382  "resolution");
1383  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1384  }
1385  break;
1386  }
1387  case vpAfma6::TOOL_VACUUM: {
1388  // Set default intrinsic camera parameters for 640x480 images
1389  if (image_width == 640 && image_height == 480) {
1390  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\""
1391  << std::endl;
1392  switch (this->projModel) {
1394  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1395  break;
1397  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1398  break;
1401  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1402  break;
1403  }
1404  }
1405  else {
1406  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1407  "resolution");
1408  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1409  }
1410  break;
1411  }
1413  // Set default intrinsic camera parameters for 640x480 images
1414  if (image_width == 640 && image_height == 480) {
1415  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_INTEL_D435_CAMERA_NAME << "\""
1416  << std::endl;
1417  switch (this->projModel) {
1419  cam.initPersProjWithoutDistortion(605.4, 605.6, 328.6, 241.0);
1420  break;
1422  cam.initPersProjWithDistortion(611.8, 612.6, 327.8, 241.7, 0.0436, -0.04265);
1423  break;
1426  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1427  break;
1428  }
1429  }
1430  else {
1431  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1432  "resolution");
1433  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1434  }
1435  break;
1436  }
1438  // Set default intrinsic camera parameters for 640x480 images
1439  if (image_width == 640 && image_height == 480) {
1440  std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\""
1441  << std::endl;
1442  switch (this->projModel) {
1444  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1445  break;
1447  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1448  break;
1451  "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1452  break;
1453  }
1454  }
1455  else {
1456  vpTRACE("Cannot get default intrinsic camera parameters for this image "
1457  "resolution");
1458  throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1459  }
1460  break;
1461  }
1462  default:
1463  vpERROR_TRACE("This error should not occur!");
1464  break;
1465  }
1466 #endif
1467  return;
1468 }
1469 
1517 {
1518  getCameraParameters(cam, I.getWidth(), I.getHeight());
1519 }
1568 {
1569  getCameraParameters(cam, I.getWidth(), I.getHeight());
1570 }
1571 
1581 VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAfma6 &afma6)
1582 {
1583  vpRotationMatrix eRc;
1584  afma6._eMc.extract(eRc);
1585  vpRxyzVector rxyz(eRc);
1586 
1587  os << "Joint Max:" << std::endl
1588  << "\t" << afma6._joint_max[0] << "\t" << afma6._joint_max[1] << "\t" << afma6._joint_max[2] << "\t"
1589  << afma6._joint_max[3] << "\t" << afma6._joint_max[4] << "\t" << afma6._joint_max[5] << "\t" << std::endl
1590 
1591  << "Joint Min: " << std::endl
1592  << "\t" << afma6._joint_min[0] << "\t" << afma6._joint_min[1] << "\t" << afma6._joint_min[2] << "\t"
1593  << afma6._joint_min[3] << "\t" << afma6._joint_min[4] << "\t" << afma6._joint_min[5] << "\t" << std::endl
1594 
1595  << "Long 5-6: " << std::endl
1596  << "\t" << afma6._long_56 << "\t" << std::endl
1597 
1598  << "Coupling 5-6:" << std::endl
1599  << "\t" << afma6._coupl_56 << "\t" << std::endl
1600 
1601  << "eMc: " << std::endl
1602  << "\tTranslation (m): " << afma6._eMc[0][3] << " " << afma6._eMc[1][3] << " " << afma6._eMc[2][3] << "\t"
1603  << std::endl
1604  << "\tRotation Rxyz (rad) : " << rxyz[0] << " " << rxyz[1] << " " << rxyz[2] << "\t" << std::endl
1605  << "\tRotation Rxyz (deg) : " << vpMath::deg(rxyz[0]) << " " << vpMath::deg(rxyz[1]) << " " << vpMath::deg(rxyz[2])
1606  << "\t" << std::endl;
1607 
1608  return os;
1609 }
1610 END_VISP_NAMESPACE
Modelization of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:78
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:93
static const char *const CONST_CCMOP_CAMERA_NAME
Definition: vpAfma6.h:101
static const std::string CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:86
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
Definition: vpAfma6.cpp:1197
static const std::string CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:85
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpAfma6.cpp:920
static const std::string CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:91
vpColVector getJointMax() const
Definition: vpAfma6.cpp:1069
static const std::string CONST_CAMERA_AFMA6_FILENAME
Definition: vpAfma6.h:95
double _joint_min[6]
Definition: vpAfma6.h:204
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Definition: vpAfma6.cpp:520
static const unsigned int njoint
Number of joint.
Definition: vpAfma6.h:194
void init(void)
Definition: vpAfma6.cpp:158
vpRxyzVector _erc
Definition: vpAfma6.h:207
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition: vpAfma6.cpp:604
static const char *const CONST_VACUUM_CAMERA_NAME
Definition: vpAfma6.h:111
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition: vpAfma6.cpp:845
static const std::string CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:87
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:898
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition: vpAfma6.h:194
vpAfma6ToolType getToolType() const
Get the current tool type.
Definition: vpAfma6.h:169
double _coupl_56
Definition: vpAfma6.h:201
static const std::string CONST_EMC_INTEL_D435_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:92
vpColVector getJointMin() const
Definition: vpAfma6.cpp:1053
static const char *const CONST_INTEL_D435_CAMERA_NAME
Definition: vpAfma6.h:122
double getCoupl56() const
Definition: vpAfma6.cpp:1083
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpAfma6.h:136
static const char *const CONST_GRIPPER_CAMERA_NAME
Definition: vpAfma6.h:106
static const std::string CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:88
vpAfma6()
Definition: vpAfma6.cpp:119
vpHomogeneousMatrix _eMc
Definition: vpAfma6.h:209
double _long_56
Definition: vpAfma6.h:202
void parseConfigFile(const std::string &filename)
Definition: vpAfma6.cpp:1103
vpTranslationVector _etc
Definition: vpAfma6.h:206
vpHomogeneousMatrix get_eMc() const
Definition: vpAfma6.cpp:909
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpAfma6.cpp:1270
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:785
static const char *const CONST_GENERIC_CAMERA_NAME
Definition: vpAfma6.h:116
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpAfma6.h:215
static const std::string CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:89
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:94
double _joint_max[6]
Definition: vpAfma6.h:203
static const std::string CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:90
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpAfma6.cpp:942
static const std::string CONST_AFMA6_FILENAME
Definition: vpAfma6.h:84
double getLong56() const
Definition: vpAfma6.cpp:1091
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:1012
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:126
@ TOOL_CCMOP
Definition: vpAfma6.h:127
@ TOOL_GENERIC_CAMERA
Definition: vpAfma6.h:130
@ TOOL_CUSTOM
Definition: vpAfma6.h:132
@ TOOL_VACUUM
Definition: vpAfma6.h:129
@ TOOL_INTEL_D435_CAMERA
Definition: vpAfma6.h:131
@ TOOL_GRIPPER
Definition: vpAfma6.h:128
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition: vpArray2D.h:362
friend std::ostream & operator<<(std::ostream &s, const vpArray2D< Type > &A)
Definition: vpArray2D.h:611
unsigned int getRows() const
Definition: vpArray2D.h:347
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ ProjWithKannalaBrandtDistortion
Projection with Kannala-Brandt distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
void initPersProjWithDistortion(double px, double py, double u0, double v0, double kud, double kdu)
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ notImplementedError
Not implemented.
Definition: vpException.h:69
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
void extract(vpRotationMatrix &R) const
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getHeight() const
Definition: vpImage.h:181
static double rad(double deg)
Definition: vpMath.h:129
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Error that can be emitted by the vpRobot class and its derivatives.
@ readingParametersError
Cannot parse parameters.
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
vpRxyzVector & build(const vpRotationMatrix &R)
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
XML parser to load and save intrinsic camera parameters.
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, bool verbose=true)
#define vpTRACE
Definition: vpDebug.h:436
#define vpERROR_TRACE
Definition: vpDebug.h:409