ViSP  2.8.0
vpAfma6.cpp
1 /****************************************************************************
2  *
3  * $Id: vpAfma6.cpp 4210 2013-04-16 08:57:46Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2013 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Interface for the Irisa's Afma6 robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
51 #include <visp/vpDebug.h>
52 #include <visp/vpVelocityTwistMatrix.h>
53 #include <visp/vpRobotException.h>
54 #include <visp/vpXmlParserCamera.h>
55 #include <visp/vpCameraParameters.h>
56 #include <visp/vpRxyzVector.h>
57 #include <visp/vpTranslationVector.h>
58 #include <visp/vpRotationMatrix.h>
59 #include <visp/vpAfma6.h>
60 
61 /* ----------------------------------------------------------------------- */
62 /* --- STATIC ------------------------------------------------------------ */
63 /* ---------------------------------------------------------------------- */
64 
65 #ifdef VISP_HAVE_ACCESS_TO_NAS
66 static const char *opt_Afma6[] = {"JOINT_MAX","JOINT_MIN","LONG_56","COUPL_56",
67  "CAMERA", "eMc_ROT_XYZ","eMc_TRANS_XYZ",
68  NULL};
69 
70 const char * const vpAfma6::CONST_AFMA6_FILENAME
71 #ifdef WIN32
72 = "Z:/robot/Afma6/current/include/const_Afma6.cnf";
73 #else
74 = "/udd/fspindle/robot/Afma6/current/include/const_Afma6.cnf";
75 #endif
76 
78 #ifdef WIN32
79 = "Z:/robot/Afma6/current/include/const_eMc_ccmop_without_distortion_Afma6.cnf";
80 #else
81 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_without_distortion_Afma6.cnf";
82 #endif
83 
85 #ifdef WIN32
86 = "Z:/robot/Afma6/current/include/const_eMc_ccmop_with_distortion_Afma6.cnf";
87 #else
88 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_ccmop_with_distortion_Afma6.cnf";
89 #endif
90 
92 #ifdef WIN32
93 = "Z:/robot/Afma6/current/include/const_eMc_gripper_without_distortion_Afma6.cnf";
94 #else
95 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_without_distortion_Afma6.cnf";
96 #endif
97 
99 #ifdef WIN32
100 = "Z:/robot/Afma6/current/include/const_eMc_gripper_with_distortion_Afma6.cnf";
101 #else
102 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_gripper_with_distortion_Afma6.cnf";
103 #endif
104 
106 #ifdef WIN32
107 = "Z:/robot/Afma6/current/include/const_eMc_vacuum_without_distortion_Afma6.cnf";
108 #else
109 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_without_distortion_Afma6.cnf";
110 #endif
111 
113 #ifdef WIN32
114 = "Z:/robot/Afma6/current/include/const_eMc_vacuum_with_distortion_Afma6.cnf";
115 #else
116 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_vacuum_with_distortion_Afma6.cnf";
117 #endif
118 
120 #ifdef WIN32
121 = "Z:/robot/Afma6/current/include/const_eMc_generic_without_distortion_Afma6.cnf";
122 #else
123 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_without_distortion_Afma6.cnf";
124 #endif
125 
127 #ifdef WIN32
128 = "Z:/robot/Afma6/current/include/const_eMc_generic_with_distortion_Afma6.cnf";
129 #else
130 = "/udd/fspindle/robot/Afma6/current/include/const_eMc_generic_with_distortion_Afma6.cnf";
131 #endif
132 
133 const char * const vpAfma6::CONST_CAMERA_AFMA6_FILENAME
134 #ifdef WIN32
135 = "Z:/robot/Afma6/current/include/const_camera_Afma6.xml";
136 #else
137 = "/udd/fspindle/robot/Afma6/current/include/const_camera_Afma6.xml";
138 #endif
139 
140 #endif // VISP_HAVE_ACCESS_TO_NAS
141 
142 const char * const vpAfma6::CONST_CCMOP_CAMERA_NAME = "Dragonfly2-8mm-ccmop";
143 const char * const vpAfma6::CONST_GRIPPER_CAMERA_NAME = "Dragonfly2-6mm-gripper";
144 const char * const vpAfma6::CONST_VACUUM_CAMERA_NAME = "Dragonfly2-6mm-vacuum";
145 const char * const vpAfma6::CONST_GENERIC_CAMERA_NAME = "Generic-camera";
146 
148 
149 const unsigned int vpAfma6::njoint = 6;
150 
157 {
158  // Set the default parameters in case of the config files on the NAS
159  // at Inria are not available.
160 
161  //
162  // Geometric model constant parameters
163  //
164  // coupling between join 5 and 6
165  this->_coupl_56 = 0.009091;
166  // distance between join 5 and 6
167  this->_long_56 = -0.06924;
168  // Camera extrinsic parameters: effector to camera frame
169  this->_eMc.setIdentity(); // Default values are initialized ...
170  // ... in init (vpAfma6::vpAfma6ToolType tool,
171  // vpCameraParameters::vpCameraParametersProjType projModel)
172  // Maximal value of the joints
173  this->_joint_max[0] = 0.7001;
174  this->_joint_max[1] = 0.5201;
175  this->_joint_max[2] = 0.4601;
176  this->_joint_max[3] = 2.7301;
177  this->_joint_max[4] = 2.4801;
178  this->_joint_max[5] = 1.5901;
179  // Minimal value of the joints
180  this->_joint_min[0] = -0.6501;
181  this->_joint_min[1] = -0.6001;
182  this->_joint_min[2] = -0.5001;
183  this->_joint_min[3] = -2.7301;
184  this->_joint_min[4] = -0.1001;
185  this->_joint_min[5] = -1.5901;
186 
187  init();
188 
189 }
190 
195 void
197 {
198  this->init ( vpAfma6::defaultTool);
199  return;
200 }
201 
216 #ifdef VISP_HAVE_ACCESS_TO_NAS
217 void
218 vpAfma6::init (const char * paramAfma6,
219  const char * paramCamera)
220 {
221  // vpTRACE ("Parsage fichier robot.");
222  this->parseConfigFile (paramAfma6);
223 
224  //vpTRACE ("Parsage fichier camera.");
225  this->parseConfigFile (paramCamera);
226 
227  return ;
228 }
229 #endif
230 
243 void
246 {
247 
248  this->projModel = projModel;
249 
250 #ifdef VISP_HAVE_ACCESS_TO_NAS
251  // Read the robot parameters from files
252  char filename_eMc [FILENAME_MAX];
253  switch (tool) {
254  case vpAfma6::TOOL_CCMOP: {
255  switch(projModel) {
257 #ifdef UNIX
258  snprintf(filename_eMc, FILENAME_MAX, "%s",
260 #else // WIN32
261  _snprintf(filename_eMc, FILENAME_MAX, "%s",
263 #endif
264  break;
266 #ifdef UNIX
267  snprintf(filename_eMc, FILENAME_MAX, "%s",
269 #else // WIN32
270  _snprintf(filename_eMc, FILENAME_MAX, "%s",
272 #endif
273  break;
274  }
275  break;
276  }
277  case vpAfma6::TOOL_GRIPPER: {
278  switch(projModel) {
280 #ifdef UNIX
281  snprintf(filename_eMc, FILENAME_MAX, "%s",
283 #else // WIN32
284  _snprintf(filename_eMc, FILENAME_MAX, "%s",
286 #endif
287  break;
289 #ifdef UNIX
290  snprintf(filename_eMc, FILENAME_MAX, "%s",
292 #else // WIN32
293  _snprintf(filename_eMc, FILENAME_MAX, "%s",
295 #endif
296  break;
297  }
298  break;
299  }
300  case vpAfma6::TOOL_VACUUM: {
301  switch(projModel) {
303 #ifdef UNIX
304  snprintf(filename_eMc, FILENAME_MAX, "%s",
306 #else // WIN32
307  _snprintf(filename_eMc, FILENAME_MAX, "%s",
309 #endif
310  break;
312 #ifdef UNIX
313  snprintf(filename_eMc, FILENAME_MAX, "%s",
315 #else // WIN32
316  _snprintf(filename_eMc, FILENAME_MAX, "%s",
318 #endif
319  break;
320  }
321  break;
322  }
324  switch(projModel) {
326 #ifdef UNIX
327  snprintf(filename_eMc, FILENAME_MAX, "%s",
329 #else // WIN32
330  _snprintf(filename_eMc, FILENAME_MAX, "%s",
332 #endif
333  break;
335 #ifdef UNIX
336  snprintf(filename_eMc, FILENAME_MAX, "%s",
338 #else // WIN32
339  _snprintf(filename_eMc, FILENAME_MAX, "%s",
341 #endif
342  break;
343  }
344  break;
345  }
346  default: {
347  vpERROR_TRACE ("This error should not occur!");
348  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
349  // "que les specs de la classe ont ete modifiee, "
350  // "et que le code n'a pas ete mis a jour "
351  // "correctement.");
352  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
353  // "vpAfma6::vpAfma6ToolType, et controlez que "
354  // "tous les cas ont ete pris en compte dans la "
355  // "fonction init(camera).");
356  break;
357  }
358  }
359 
360  this->init (vpAfma6::CONST_AFMA6_FILENAME, filename_eMc);
361 
362 #else // VISP_HAVE_ACCESS_TO_NAS
363 
364  // Use here default values of the robot constant parameters.
365  switch (tool) {
366  case vpAfma6::TOOL_CCMOP: {
367  switch(projModel) {
369  _erc[0] = vpMath::rad(164.35); // rx
370  _erc[1] = vpMath::rad( 89.64); // ry
371  _erc[2] = vpMath::rad(-73.05); // rz
372  _etc[0] = 0.0117; // tx
373  _etc[1] = 0.0033; // ty
374  _etc[2] = 0.2272; // tz
375  break;
377  _erc[0] = vpMath::rad(33.54); // rx
378  _erc[1] = vpMath::rad(89.34); // ry
379  _erc[2] = vpMath::rad(57.83); // rz
380  _etc[0] = 0.0373; // tx
381  _etc[1] = 0.0024; // ty
382  _etc[2] = 0.2286; // tz
383  break;
384  }
385  }
386  case vpAfma6::TOOL_GRIPPER: {
387  switch(projModel) {
389  _erc[0] = vpMath::rad( 88.33); // rx
390  _erc[1] = vpMath::rad( 72.07); // ry
391  _erc[2] = vpMath::rad( 2.53); // rz
392  _etc[0] = 0.0783; // tx
393  _etc[1] = 0.1234; // ty
394  _etc[2] = 0.1638; // tz
395  break;
397  _erc[0] = vpMath::rad(86.69); // rx
398  _erc[1] = vpMath::rad(71.93); // ry
399  _erc[2] = vpMath::rad( 4.17); // rz
400  _etc[0] = 0.1034; // tx
401  _etc[1] = 0.1142; // ty
402  _etc[2] = 0.1642; // tz
403  break;
404  }
405  }
406  case vpAfma6::TOOL_VACUUM: {
407  switch(projModel) {
409  _erc[0] = vpMath::rad( 90.40); // rx
410  _erc[1] = vpMath::rad( 75.11); // ry
411  _erc[2] = vpMath::rad( 0.18); // rz
412  _etc[0] = 0.0038; // tx
413  _etc[1] = 0.1281; // ty
414  _etc[2] = 0.1658; // tz
415  break;
417  _erc[0] = vpMath::rad(91.61); // rx
418  _erc[1] = vpMath::rad(76.17); // ry
419  _erc[2] = vpMath::rad(-0.98); // rz
420  _etc[0] = 0.0815; // tx
421  _etc[1] = 0.1162; // ty
422  _etc[2] = 0.1658; // tz
423  break;
424  }
425  }
427  switch(projModel) {
430  // set eMc to identity
431  _erc[0] = 0; // rx
432  _erc[1] = 0; // ry
433  _erc[2] = 0; // rz
434  _etc[0] = 0; // tx
435  _etc[1] = 0; // ty
436  _etc[2] = 0; // tz
437  break;
438  }
439  }
440  }
441  vpRotationMatrix eRc(_erc);
442  this->_eMc.buildFrom(_etc, eRc);
443 #endif // VISP_HAVE_ACCESS_TO_NAS
444 
445  setToolType(tool);
446  return ;
447 }
448 
449 
476 {
478  fMc = get_fMc(q);
479 
480  return fMc;
481 }
482 
556 int
558  vpColVector & q, const bool &nearest, const bool &verbose)
559 {
561  double q_[2][6],d[2],t;
562  int ok[2];
563  double cord[6];
564 
565  int nbsol = 0;
566 
567  if (q.getRows() != njoint)
568  q.resize(6);
569 
570 
571  // for(unsigned int i=0;i<3;i++) {
572  // fMe[i][3] = fMc[i][3];
573  // for(int j=0;j<3;j++) {
574  // fMe[i][j] = 0.0;
575  // for (int k=0;k<3;k++) fMe[i][j] += fMc[i][k]*rpi[j][k];
576  // fMe[i][3] -= fMe[i][j]*rpi[j][3];
577  // }
578  // }
579 
580  // std::cout << "\n\nfMc: " << fMc;
581  // std::cout << "\n\neMc: " << _eMc;
582 
583  fMe = fMc * this->_eMc.inverse();
584  // std::cout << "\n\nfMe: " << fMe;
585 
586  if (fMe[2][2] >= .99999f)
587  {
588  vpTRACE("singularity\n");
589  q_[0][4] = q_[1][4] = M_PI/2.f;
590  t = atan2(fMe[0][0],fMe[0][1]);
591  q_[1][3] = q_[0][3] = q[3];
592  q_[1][5] = q_[0][5] = t - q_[0][3];
593 
594  while ((q_[1][5]+vpMath::rad(2)) >= this->_joint_max[5])
595  /* -> a cause du couplage 4/5 */
596  {
597  q_[1][5] -= vpMath::rad(10);
598  q_[1][3] += vpMath::rad(10);
599  }
600  while (q_[1][5] <= this->_joint_min[5])
601  {
602  q_[1][5] += vpMath::rad(10);
603  q_[1][3] -= vpMath::rad(10);
604  }
605  }
606  else if (fMe[2][2] <= -.99999)
607  {
608  vpTRACE("singularity\n");
609  q_[0][4] = q_[1][4] = -M_PI/2;
610  t = atan2(fMe[1][1],fMe[1][0]);
611  q_[1][3] = q_[0][3] = q[3];
612  q_[1][5] = q_[0][5] = q_[0][3] - t;
613  while ((q_[1][5]+vpMath::rad(2)) >= this->_joint_max[5])
614  /* -> a cause du couplage 4/5 */
615  {
616  q_[1][5] -= vpMath::rad(10);
617  q_[1][3] -= vpMath::rad(10);
618  }
619  while (q_[1][5] <= this->_joint_min[5])
620  {
621  q_[1][5] += vpMath::rad(10);
622  q_[1][3] += vpMath::rad(10);
623  }
624  }
625  else
626  {
627  q_[0][3] = atan2(-fMe[0][2],fMe[1][2]);
628  if (q_[0][3] >= 0.0) q_[1][3] = q_[0][3] - M_PI;
629  else q_[1][3] = q_[0][3] + M_PI;
630 
631  q_[0][4] = asin(fMe[2][2]);
632  if (q_[0][4] >= 0.0) q_[1][4] = M_PI - q_[0][4];
633  else q_[1][4] = -M_PI - q_[0][4];
634 
635  q_[0][5] = atan2(-fMe[2][1],fMe[2][0]);
636  if (q_[0][5] >= 0.0) q_[1][5] = q_[0][5] - M_PI;
637  else q_[1][5] = q_[0][5] + M_PI;
638  }
639  q_[0][0] = fMe[0][3] - this->_long_56*cos(q_[0][3]);
640  q_[1][0] = fMe[0][3] - this->_long_56*cos(q_[1][3]);
641  q_[0][1] = fMe[1][3] - this->_long_56*sin(q_[0][3]);
642  q_[1][1] = fMe[1][3] - this->_long_56*sin(q_[1][3]);
643  q_[0][2] = q_[1][2] = fMe[2][3];
644 
645  /* prise en compte du couplage axes 5/6 */
646  q_[0][5] += this->_coupl_56*q_[0][4];
647  q_[1][5] += this->_coupl_56*q_[1][4];
648 
649  for (int j=0;j<2;j++)
650  {
651  ok[j] = 1;
652  // test is position is reachable
653  for (unsigned int i=0;i<6;i++) {
654  if (q_[j][i] < this->_joint_min[i] || q_[j][i] > this->_joint_max[i]) {
655  if (verbose) {
656  if (i < 3)
657  std::cout << "Joint " << i << " not in limits: " << this->_joint_min[i] << " < " << q_[j][i] << " < " << this->_joint_max[i] << std::endl;
658  else
659  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;
660  }
661  ok[j] = 0;
662  }
663  }
664  }
665  if (ok[0] == 0)
666  {
667  if (ok[1] == 0) {
668  std::cout << "No solution..." << std::endl;
669  nbsol = 0;
670  return nbsol;
671  }
672  else if (ok[1] == 1) {
673  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
674  nbsol = 1;
675  }
676  }
677  else
678  {
679  if (ok[1] == 0) {
680  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
681  nbsol = 1;
682  }
683  else
684  {
685  nbsol = 2;
686  //vpTRACE("2 solutions\n");
687  for (int j=0;j<2;j++)
688  {
689  d[j] = 0.0;
690  for (unsigned int i=3;i<6;i++)
691  d[j] += (q_[j][i] - q[i]) * (q_[j][i] - q[i]);
692  }
693  if (nearest == true)
694  {
695  if (d[0] <= d[1])
696  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
697  else
698  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
699  }
700  else
701  {
702  if (d[0] <= d[1])
703  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
704  else
705  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
706  }
707  }
708  }
709  for(unsigned int i=0; i<6; i++)
710  q[i] = cord[i] ;
711 
712  return nbsol;
713 }
714 
739 {
741  get_fMc(q, fMc);
742 
743  return fMc;
744 }
745 
765 void
767 {
768 
769  // Compute the direct geometric model: fMe = transformation between
770  // fix and end effector frame.
772 
773  get_fMe(q, fMe);
774 
775  fMc = fMe * this->_eMc;
776 
777  return;
778 }
779 
799 void
801 {
802  double q0 = q[0]; // meter
803  double q1 = q[1]; // meter
804  double q2 = q[2]; // meter
805 
806  /* Decouplage liaisons 2 et 3. */
807  double q5 = q[5] - this->_coupl_56 * q[4];
808 
809  double c1 = cos(q[3]);
810  double s1 = sin(q[3]);
811  double c2 = cos(q[4]);
812  double s2 = sin(q[4]);
813  double c3 = cos(q5);
814  double s3 = sin(q5);
815 
816  // Compute the direct geometric model: fMe = transformation betwee
817  // fix and end effector frame.
818  fMe[0][0] = s1*s2*c3 + c1*s3;
819  fMe[0][1] = -s1*s2*s3 + c1*c3;
820  fMe[0][2] = -s1*c2;
821  fMe[0][3] = q0 + this->_long_56*c1;
822 
823  fMe[1][0] = -c1*s2*c3 + s1*s3;
824  fMe[1][1] = c1*s2*s3 + s1*c3;
825  fMe[1][2] = c1*c2;
826  fMe[1][3] = q1 + this->_long_56*s1;
827 
828  fMe[2][0] = c2*c3;
829  fMe[2][1] = -c2*s3;
830  fMe[2][2] = s2;
831  fMe[2][3] = q2;
832 
833  fMe[3][0] = 0;
834  fMe[3][1] = 0;
835  fMe[3][2] = 0;
836  fMe[3][3] = 1;
837 
838  // vpCTRACE << "Effector position fMe: " << std::endl << fMe;
839 
840  return;
841 }
842 
853 void
855 {
856  cMe = this->_eMc.inverse();
857 }
858 
868 void
870 {
871  vpHomogeneousMatrix cMe ;
872  get_cMe(cMe) ;
873 
874  cVe.buildFrom(cMe) ;
875 
876  return;
877 }
878 
891 void
893 {
894 
895  eJe.resize(6,6) ;
896 
897  double s3,c3,s4,c4,s5,c5 ;
898 
899  s3=sin(q[3]); c3=cos(q[3]);
900  s4=sin(q[4]); c4=cos(q[4]);
901  s5=sin(q[5]); c5=cos(q[5]);
902 
903  eJe = 0;
904  eJe[0][0] = s3*s4*c5+c3*s5;
905  eJe[0][1] = -c3*s4*c5+s3*s5;
906  eJe[0][2] = c4*c5;
907  eJe[0][3] = - this->_long_56*s4*c5;
908 
909  eJe[1][0] = -s3*s4*s5+c3*c5;
910  eJe[1][1] = c3*s4*s5+s3*c5;
911  eJe[1][2] = -c4*s5;
912  eJe[1][3] = this->_long_56*s4*s5;
913 
914  eJe[2][0] = -s3*c4;
915  eJe[2][1] = c3*c4;
916  eJe[2][2] = s4;
917  eJe[2][3] = this->_long_56*c4;
918 
919  eJe[3][3] = c4*c5;
920  eJe[3][4] = s5;
921 
922  eJe[4][3] = -c4*s5;
923  eJe[4][4] = c5;
924 
925  eJe[5][3] = s4;
926  eJe[5][5] = 1;
927 
928  return;
929 }
930 
931 
958 void
960 {
961 
962  fJe.resize(6,6) ;
963 
964  // block superieur gauche
965  fJe[0][0] = fJe[1][1] = fJe[2][2] = 1 ;
966 
967  double s4 = sin(q[4]) ;
968  double c4 = cos(q[4]) ;
969 
970 
971  // block superieur droit
972  fJe[0][3] = - this->_long_56*s4 ;
973  fJe[1][3] = this->_long_56*c4 ;
974 
975 
976  double s5 = sin(q[5]) ;
977  double c5 = cos(q[5]) ;
978  // block inferieur droit
979  fJe[3][4] = c4 ; fJe[3][5] = -s4*c5 ;
980  fJe[4][4] = s4 ; fJe[4][5] = c4*c5 ;
981  fJe[5][3] = 1 ; fJe[5][5] = s5 ;
982 
983  return;
984 }
985 
986 
997 {
998  vpColVector qmin(6);
999  for (unsigned int i=0; i < 6; i ++)
1000  qmin[i] = this->_joint_min[i];
1001  return qmin;
1002 }
1003 
1014 {
1015  vpColVector qmax(6);
1016  for (unsigned int i=0; i < 6; i ++)
1017  qmax[i] = this->_joint_max[i];
1018  return qmax;
1019 }
1020 
1027 double
1029 {
1030  return _coupl_56;
1031 }
1032 
1039 double
1041 {
1042  return _long_56;
1043 }
1044 
1045 
1058 #ifdef VISP_HAVE_ACCESS_TO_NAS
1059 void
1060 vpAfma6::parseConfigFile (const char * filename)
1061 {
1062  size_t dim;
1063  int code;
1064  char Ligne[FILENAME_MAX];
1065  char namoption[100];
1066  FILE * fdtask;
1067  int numLn = 0;
1068  double rot_eMc[3]; // rotation
1069  double trans_eMc[3]; // translation
1070  bool get_rot_eMc = false;
1071  bool get_trans_eMc = false;
1072 
1073  //vpTRACE("Read the config file for constant parameters %s.", filename);
1074  if ((fdtask = fopen(filename, "r" )) == NULL)
1075  {
1076  vpERROR_TRACE ("Impossible to read the config file %s.",
1077  filename);
1079  "Impossible to read the config file.");
1080  }
1081 
1082  while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
1083  numLn ++;
1084  if ('#' == Ligne[0]) { continue; }
1085  sscanf(Ligne, "%s", namoption);
1086  dim = strlen(namoption);
1087 
1088  for (code = 0;
1089  NULL != opt_Afma6[code];
1090  ++ code)
1091  {
1092  if (strncmp(opt_Afma6[code], namoption, dim) == 0)
1093  {
1094  break;
1095  }
1096  }
1097 
1098  switch(code)
1099  {
1100  case 0:
1101  sscanf(Ligne, "%s %lf %lf %lf %lf %lf %lf",
1102  namoption,
1103  &this->_joint_max[0], &this->_joint_max[1],
1104  &this->_joint_max[2], &this->_joint_max[3],
1105  &this->_joint_max[4], &this->_joint_max[5]);
1106  break;
1107 
1108  case 1:
1109  sscanf(Ligne, "%s %lf %lf %lf %lf %lf %lf", namoption,
1110  &this->_joint_min[0], &this->_joint_min[1],
1111  &this->_joint_min[2], &this->_joint_min[3],
1112  &this->_joint_min[4], &this->_joint_min[5]);
1113  break;
1114 
1115  case 2:
1116  sscanf(Ligne, "%s %lf", namoption, &this->_long_56);
1117  break;
1118 
1119  case 3:
1120  sscanf(Ligne, "%s %lf", namoption, &this->_coupl_56);
1121  break;
1122 
1123  case 4:
1124  break; // Nothing to do: camera name
1125 
1126  case 5:
1127  sscanf(Ligne, "%s %lf %lf %lf", namoption,
1128  &rot_eMc[0],
1129  &rot_eMc[1],
1130  &rot_eMc[2]);
1131 
1132  // Convert rotation from degrees to radians
1133  rot_eMc[0] *= M_PI / 180.0;
1134  rot_eMc[1] *= M_PI / 180.0;
1135  rot_eMc[2] *= M_PI / 180.0;
1136  get_rot_eMc = true;
1137  break;
1138 
1139  case 6:
1140  sscanf(Ligne, "%s %lf %lf %lf", namoption,
1141  &trans_eMc[0],
1142  &trans_eMc[1],
1143  &trans_eMc[2]);
1144  get_trans_eMc = true;
1145  break;
1146 
1147  default:
1148  vpERROR_TRACE ("Bad configuration file %s "
1149  "ligne #%d.", filename, numLn);
1150  } /* SWITCH */
1151  } /* WHILE */
1152 
1153  fclose (fdtask);
1154 
1155  // Compute the eMc matrix from the translations and rotations
1156  if (get_rot_eMc && get_trans_eMc) {
1157  for (unsigned int i=0; i < 3; i ++) {
1158  _erc[i] = rot_eMc[i];
1159  _etc[i] = trans_eMc[i];
1160  }
1161 
1162  vpRotationMatrix eRc(_erc);
1163  this->_eMc.buildFrom(_etc, eRc);
1164  }
1165 
1166  return;
1167 }
1168 #endif
1169 
1233 void
1235  const unsigned int &image_width,
1236  const unsigned int &image_height)
1237 {
1238 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
1239  vpXmlParserCamera parser;
1240  switch (getToolType()) {
1241  case vpAfma6::TOOL_CCMOP: {
1242  std::cout << "Get camera parameters for camera \""
1243  << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl
1244  << "from the XML file: \""
1245  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1246  if (parser.parse(cam,
1249  projModel,
1250  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1252  "Impossible to read the camera parameters.");
1253  }
1254  break;
1255  }
1256  case vpAfma6::TOOL_GRIPPER: {
1257  std::cout << "Get camera parameters for camera \""
1258  << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl
1259  << "from the XML file: \""
1260  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1261  if (parser.parse(cam,
1264  projModel,
1265  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1267  "Impossible to read the camera parameters.");
1268  }
1269  break;
1270  }
1271  case vpAfma6::TOOL_VACUUM: {
1272  std::cout << "Get camera parameters for camera \""
1273  << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl
1274  << "from the XML file: \""
1275  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1276  if (parser.parse(cam,
1279  projModel,
1280  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1282  "Impossible to read the camera parameters.");
1283  }
1284  break;
1285  }
1287  std::cout << "Get camera parameters for camera \""
1288  << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
1289  << "from the XML file: \""
1290  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1291  if (parser.parse(cam,
1294  projModel,
1295  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1297  "Impossible to read the camera parameters.");
1298  }
1299  break;
1300  }
1301  default: {
1302  vpERROR_TRACE ("This error should not occur!");
1303  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
1304  // "que les specs de la classe ont ete modifiee, "
1305  // "et que le code n'a pas ete mis a jour "
1306  // "correctement.");
1307  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
1308  // "vpAfma6::vpAfma6ToolType, et controlez que "
1309  // "tous les cas ont ete pris en compte dans la "
1310  // "fonction init(camera).");
1312  "Impossible to read the camera parameters.");
1313  break;
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)
1455 {
1456  getCameraParameters(cam,I.getWidth(),I.getHeight());
1457 }
1501 void
1503  const vpImage<vpRGBa> &I)
1504 {
1505  getCameraParameters(cam,I.getWidth(),I.getHeight());
1506 }
1507 
1508 
1518 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 /*
1572  * Local variables:
1573  * c-basic-offset: 2
1574  * End:
1575  */
Modelisation of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:69
Definition of the vpMatrix class.
Definition: vpMatrix.h:96
vpRxyzVector _erc
Definition: vpAfma6.h:188
vpTranslationVector _etc
Definition: vpAfma6.h:187
static const unsigned int njoint
Number of joint.
Definition: vpAfma6.h:174
void resize(const unsigned int nrows, const unsigned int ncols, const bool nullify=true)
Definition: vpMatrix.cpp:174
Error that can be emited by the vpRobot class and its derivates.
static const char *const CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:79
Perspective projection without distortion model.
static const char *const CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:78
unsigned int getWidth() const
Definition: vpImage.h:159
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
#define vpERROR_TRACE
Definition: vpDebug.h:379
#define vpTRACE
Definition: vpDebug.h:401
void get_cVe(vpVelocityTwistMatrix &cVe)
Definition: vpAfma6.cpp:869
void setIdentity()
Basic initialisation (identity)
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpAfma6.cpp:738
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
Definition: vpAfma6.cpp:1234
double _coupl_56
Definition: vpAfma6.h:182
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:108
vpCameraParameters::vpCameraParametersProjType projModel
Definition: vpAfma6.h:196
static const char *const CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:82
XML parser to load and save intrinsic camera parameters.
vpAfma6ToolType getToolType()
Get the current tool type.
Definition: vpAfma6.h:147
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition: vpAfma6.h:172
static const char *const CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:81
static const char *const CONST_GRIPPER_CAMERA_NAME
Definition: vpAfma6.h:95
The vpRotationMatrix considers the particular case of a rotation matrix.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpAfma6.cpp:854
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpAfma6.h:117
static const char *const CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:77
static const char *const CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition: vpAfma6.h:83
void get_eJe(const vpColVector &q, vpMatrix &eJe)
Definition: vpAfma6.cpp:892
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static const char *const CONST_CAMERA_AFMA6_FILENAME
Definition: vpAfma6.h:85
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false)
Definition: vpAfma6.cpp:557
static const char *const CONST_AFMA6_FILENAME
Definition: vpAfma6.h:76
Generic class defining intrinsic camera parameters.
void parseConfigFile(const char *filename)
Definition: vpAfma6.cpp:1060
void extract(vpRotationMatrix &R) const
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe)
Definition: vpAfma6.cpp:800
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q)
Definition: vpAfma6.cpp:475
VISP_EXPORT std::ostream & operator<<(std::ostream &os, const vpImagePoint &ip)
Definition: vpImagePoint.h:529
vpAfma6()
Definition: vpAfma6.cpp:156
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Construction from translation vector and rotation matrix.
static double rad(double deg)
Definition: vpMath.h:100
int parse(vpCameraParameters &cam, const char *filename, const std::string &camera_name, const vpCameraParameters::vpCameraParametersProjType &projModel, const unsigned int image_width=0, const unsigned int image_height=0)
double _long_56
Definition: vpAfma6.h:183
static double deg(double rad)
Definition: vpMath.h:93
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
static const char *const CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:80
vpHomogeneousMatrix inverse() const
vpHomogeneousMatrix _eMc
Definition: vpAfma6.h:190
vpColVector getJointMin()
Definition: vpAfma6.cpp:996
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpAfma6.cpp:959
unsigned int getHeight() const
Definition: vpImage.h:150
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
Definition: vpRxyzVector.h:152
vpColVector getJointMax()
Definition: vpAfma6.cpp:1013
void init(void)
Definition: vpAfma6.cpp:196
double _joint_max[6]
Definition: vpAfma6.h:184
unsigned int getRows() const
Return the number of rows of the matrix.
Definition: vpMatrix.h:157
double getCoupl56()
Definition: vpAfma6.cpp:1028
static const char *const CONST_CCMOP_CAMERA_NAME
Definition: vpAfma6.h:90
static const char *const CONST_VACUUM_CAMERA_NAME
Definition: vpAfma6.h:100
void initPersProjWithDistortion(const double px, const double py, const double u0, const double v0, const double kud, const double kdu)
double getLong56()
Definition: vpAfma6.cpp:1040
static const char *const CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition: vpAfma6.h:84
double _joint_min[6]
Definition: vpAfma6.h:185
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:94
static const char *const CONST_GENERIC_CAMERA_NAME
Definition: vpAfma6.h:105