ViSP  2.6.2
vpAfma6.cpp
1 /****************************************************************************
2  *
3  * $Id: vpAfma6.cpp 3842 2012-07-13 22:21:42Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 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 
554 int
556  vpColVector & q, const bool &nearest)
557 {
559  double q_[2][6],d[2],t;
560  int ok[2];
561  double cord[6];
562 
563  int nbsol = 0;
564 
565  if (q.getRows() != njoint)
566  q.resize(6);
567 
568 
569  // for(unsigned int i=0;i<3;i++) {
570  // fMe[i][3] = fMc[i][3];
571  // for(int j=0;j<3;j++) {
572  // fMe[i][j] = 0.0;
573  // for (int k=0;k<3;k++) fMe[i][j] += fMc[i][k]*rpi[j][k];
574  // fMe[i][3] -= fMe[i][j]*rpi[j][3];
575  // }
576  // }
577 
578  // std::cout << "\n\nfMc: " << fMc;
579  // std::cout << "\n\neMc: " << _eMc;
580 
581  fMe = fMc * this->_eMc.inverse();
582  // std::cout << "\n\nfMe: " << fMe;
583 
584  if (fMe[2][2] >= .99999f)
585  {
586  vpTRACE("singularity\n");
587  q_[0][4] = q_[1][4] = M_PI/2.f;
588  t = atan2(fMe[0][0],fMe[0][1]);
589  q_[1][3] = q_[0][3] = q[3];
590  q_[1][5] = q_[0][5] = t - q_[0][3];
591 
592  while ((q_[1][5]+vpMath::rad(2)) >= this->_joint_max[5])
593  /* -> a cause du couplage 4/5 */
594  {
595  q_[1][5] -= vpMath::rad(10);
596  q_[1][3] += vpMath::rad(10);
597  }
598  while (q_[1][5] <= this->_joint_min[5])
599  {
600  q_[1][5] += vpMath::rad(10);
601  q_[1][3] -= vpMath::rad(10);
602  }
603  }
604  else if (fMe[2][2] <= -.99999)
605  {
606  vpTRACE("singularity\n");
607  q_[0][4] = q_[1][4] = -M_PI/2;
608  t = atan2(fMe[1][1],fMe[1][0]);
609  q_[1][3] = q_[0][3] = q[3];
610  q_[1][5] = q_[0][5] = q_[0][3] - t;
611  while ((q_[1][5]+vpMath::rad(2)) >= this->_joint_max[5])
612  /* -> a cause du couplage 4/5 */
613  {
614  q_[1][5] -= vpMath::rad(10);
615  q_[1][3] -= vpMath::rad(10);
616  }
617  while (q_[1][5] <= this->_joint_min[5])
618  {
619  q_[1][5] += vpMath::rad(10);
620  q_[1][3] += vpMath::rad(10);
621  }
622  }
623  else
624  {
625  q_[0][3] = atan2(-fMe[0][2],fMe[1][2]);
626  if (q_[0][3] >= 0.0) q_[1][3] = q_[0][3] - M_PI;
627  else q_[1][3] = q_[0][3] + M_PI;
628 
629  q_[0][4] = asin(fMe[2][2]);
630  if (q_[0][4] >= 0.0) q_[1][4] = M_PI - q_[0][4];
631  else q_[1][4] = -M_PI - q_[0][4];
632 
633  q_[0][5] = atan2(-fMe[2][1],fMe[2][0]);
634  if (q_[0][5] >= 0.0) q_[1][5] = q_[0][5] - M_PI;
635  else q_[1][5] = q_[0][5] + M_PI;
636  }
637  q_[0][0] = fMe[0][3] - this->_long_56*cos(q_[0][3]);
638  q_[1][0] = fMe[0][3] - this->_long_56*cos(q_[1][3]);
639  q_[0][1] = fMe[1][3] - this->_long_56*sin(q_[0][3]);
640  q_[1][1] = fMe[1][3] - this->_long_56*sin(q_[1][3]);
641  q_[0][2] = q_[1][2] = fMe[2][3];
642 
643  /* prise en compte du couplage axes 5/6 */
644  q_[0][5] += this->_coupl_56*q_[0][4];
645  q_[1][5] += this->_coupl_56*q_[1][4];
646 
647  for (int j=0;j<2;j++)
648  {
649  ok[j] = 1;
650  // test is position is reachable
651  for (unsigned int i=0;i<6;i++) {
652  if (q_[j][i] < this->_joint_min[i] || q_[j][i] > this->_joint_max[i])
653  ok[j] = 0;
654  }
655  }
656  if (ok[0] == 0)
657  {
658  if (ok[1] == 0) {
659  std::cout << "No solution..." << std::endl;
660  nbsol = 0;
661  return nbsol;
662  }
663  else if (ok[1] == 1) {
664  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
665  nbsol = 1;
666  }
667  }
668  else
669  {
670  if (ok[1] == 0) {
671  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
672  nbsol = 1;
673  }
674  else
675  {
676  nbsol = 2;
677  //vpTRACE("2 solutions\n");
678  for (int j=0;j<2;j++)
679  {
680  d[j] = 0.0;
681  for (unsigned int i=3;i<6;i++)
682  d[j] += (q_[j][i] - q[i]) * (q_[j][i] - q[i]);
683  }
684  if (nearest == true)
685  {
686  if (d[0] <= d[1])
687  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
688  else
689  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
690  }
691  else
692  {
693  if (d[0] <= d[1])
694  for (unsigned int i=0;i<6;i++) cord[i] = q_[1][i];
695  else
696  for (unsigned int i=0;i<6;i++) cord[i] = q_[0][i];
697  }
698  }
699  }
700  for(unsigned int i=0; i<6; i++)
701  q[i] = cord[i] ;
702 
703  return nbsol;
704 }
705 
730 {
732  get_fMc(q, fMc);
733 
734  return fMc;
735 }
736 
756 void
758 {
759 
760  // Compute the direct geometric model: fMe = transformation between
761  // fix and end effector frame.
763 
764  get_fMe(q, fMe);
765 
766  fMc = fMe * this->_eMc;
767 
768  return;
769 }
770 
790 void
792 {
793  double q0 = q[0]; // meter
794  double q1 = q[1]; // meter
795  double q2 = q[2]; // meter
796 
797  /* Decouplage liaisons 2 et 3. */
798  double q5 = q[5] - this->_coupl_56 * q[4];
799 
800  double c1 = cos(q[3]);
801  double s1 = sin(q[3]);
802  double c2 = cos(q[4]);
803  double s2 = sin(q[4]);
804  double c3 = cos(q5);
805  double s3 = sin(q5);
806 
807  // Compute the direct geometric model: fMe = transformation betwee
808  // fix and end effector frame.
809  fMe[0][0] = s1*s2*c3 + c1*s3;
810  fMe[0][1] = -s1*s2*s3 + c1*c3;
811  fMe[0][2] = -s1*c2;
812  fMe[0][3] = q0 + this->_long_56*c1;
813 
814  fMe[1][0] = -c1*s2*c3 + s1*s3;
815  fMe[1][1] = c1*s2*s3 + s1*c3;
816  fMe[1][2] = c1*c2;
817  fMe[1][3] = q1 + this->_long_56*s1;
818 
819  fMe[2][0] = c2*c3;
820  fMe[2][1] = -c2*s3;
821  fMe[2][2] = s2;
822  fMe[2][3] = q2;
823 
824  fMe[3][0] = 0;
825  fMe[3][1] = 0;
826  fMe[3][2] = 0;
827  fMe[3][3] = 1;
828 
829  // vpCTRACE << "Effector position fMe: " << std::endl << fMe;
830 
831  return;
832 }
833 
844 void
846 {
847  cMe = this->_eMc.inverse();
848 }
849 
859 void
861 {
862  vpHomogeneousMatrix cMe ;
863  get_cMe(cMe) ;
864 
865  cVe.buildFrom(cMe) ;
866 
867  return;
868 }
869 
882 void
884 {
885 
886  eJe.resize(6,6) ;
887 
888  double s3,c3,s4,c4,s5,c5 ;
889 
890  s3=sin(q[3]); c3=cos(q[3]);
891  s4=sin(q[4]); c4=cos(q[4]);
892  s5=sin(q[5]); c5=cos(q[5]);
893 
894  eJe = 0;
895  eJe[0][0] = s3*s4*c5+c3*s5;
896  eJe[0][1] = -c3*s4*c5+s3*s5;
897  eJe[0][2] = c4*c5;
898  eJe[0][3] = - this->_long_56*s4*c5;
899 
900  eJe[1][0] = -s3*s4*s5+c3*c5;
901  eJe[1][1] = c3*s4*s5+s3*c5;
902  eJe[1][2] = -c4*s5;
903  eJe[1][3] = this->_long_56*s4*s5;
904 
905  eJe[2][0] = -s3*c4;
906  eJe[2][1] = c3*c4;
907  eJe[2][2] = s4;
908  eJe[2][3] = this->_long_56*c4;
909 
910  eJe[3][3] = c4*c5;
911  eJe[3][4] = s5;
912 
913  eJe[4][3] = -c4*s5;
914  eJe[4][4] = c5;
915 
916  eJe[5][3] = s4;
917  eJe[5][5] = 1;
918 
919  return;
920 }
921 
922 
949 void
951 {
952 
953  fJe.resize(6,6) ;
954 
955  // block superieur gauche
956  fJe[0][0] = fJe[1][1] = fJe[2][2] = 1 ;
957 
958  double s4 = sin(q[4]) ;
959  double c4 = cos(q[4]) ;
960 
961 
962  // block superieur droit
963  fJe[0][3] = - this->_long_56*s4 ;
964  fJe[1][3] = this->_long_56*c4 ;
965 
966 
967  double s5 = sin(q[5]) ;
968  double c5 = cos(q[5]) ;
969  // block inferieur droit
970  fJe[3][4] = c4 ; fJe[3][5] = -s4*c5 ;
971  fJe[4][4] = s4 ; fJe[4][5] = c4*c5 ;
972  fJe[5][3] = 1 ; fJe[5][5] = s5 ;
973 
974  return;
975 }
976 
977 
988 {
989  vpColVector qmin(6);
990  for (unsigned int i=0; i < 6; i ++)
991  qmin[i] = this->_joint_min[i];
992  return qmin;
993 }
994 
1005 {
1006  vpColVector qmax(6);
1007  for (unsigned int i=0; i < 6; i ++)
1008  qmax[i] = this->_joint_max[i];
1009  return qmax;
1010 }
1011 
1018 double
1020 {
1021  return _coupl_56;
1022 }
1023 
1030 double
1032 {
1033  return _long_56;
1034 }
1035 
1036 
1049 #ifdef VISP_HAVE_ACCESS_TO_NAS
1050 void
1051 vpAfma6::parseConfigFile (const char * filename)
1052 {
1053  size_t dim;
1054  int code;
1055  char Ligne[FILENAME_MAX];
1056  char namoption[100];
1057  FILE * fdtask;
1058  int numLn = 0;
1059  double rot_eMc[3]; // rotation
1060  double trans_eMc[3]; // translation
1061  bool get_rot_eMc = false;
1062  bool get_trans_eMc = false;
1063 
1064  //vpTRACE("Read the config file for constant parameters %s.", filename);
1065  if ((fdtask = fopen(filename, "r" )) == NULL)
1066  {
1067  vpERROR_TRACE ("Impossible to read the config file %s.",
1068  filename);
1069  fclose(fdtask);
1071  "Impossible to read the config file.");
1072  }
1073 
1074  while (fgets(Ligne, FILENAME_MAX, fdtask) != NULL) {
1075  numLn ++;
1076  if ('#' == Ligne[0]) { continue; }
1077  sscanf(Ligne, "%s", namoption);
1078  dim = strlen(namoption);
1079 
1080  for (code = 0;
1081  NULL != opt_Afma6[code];
1082  ++ code)
1083  {
1084  if (strncmp(opt_Afma6[code], namoption, dim) == 0)
1085  {
1086  break;
1087  }
1088  }
1089 
1090  switch(code)
1091  {
1092  case 0:
1093  sscanf(Ligne, "%s %lf %lf %lf %lf %lf %lf",
1094  namoption,
1095  &this->_joint_max[0], &this->_joint_max[1],
1096  &this->_joint_max[2], &this->_joint_max[3],
1097  &this->_joint_max[4], &this->_joint_max[5]);
1098  break;
1099 
1100  case 1:
1101  sscanf(Ligne, "%s %lf %lf %lf %lf %lf %lf", namoption,
1102  &this->_joint_min[0], &this->_joint_min[1],
1103  &this->_joint_min[2], &this->_joint_min[3],
1104  &this->_joint_min[4], &this->_joint_min[5]);
1105  break;
1106 
1107  case 2:
1108  sscanf(Ligne, "%s %lf", namoption, &this->_long_56);
1109  break;
1110 
1111  case 3:
1112  sscanf(Ligne, "%s %lf", namoption, &this->_coupl_56);
1113  break;
1114 
1115  case 4:
1116  break; // Nothing to do: camera name
1117 
1118  case 5:
1119  sscanf(Ligne, "%s %lf %lf %lf", namoption,
1120  &rot_eMc[0],
1121  &rot_eMc[1],
1122  &rot_eMc[2]);
1123 
1124  // Convert rotation from degrees to radians
1125  rot_eMc[0] *= M_PI / 180.0;
1126  rot_eMc[1] *= M_PI / 180.0;
1127  rot_eMc[2] *= M_PI / 180.0;
1128  get_rot_eMc = true;
1129  break;
1130 
1131  case 6:
1132  sscanf(Ligne, "%s %lf %lf %lf", namoption,
1133  &trans_eMc[0],
1134  &trans_eMc[1],
1135  &trans_eMc[2]);
1136  get_trans_eMc = true;
1137  break;
1138 
1139  default:
1140  vpERROR_TRACE ("Bad configuration file %s "
1141  "ligne #%d.", filename, numLn);
1142  } /* SWITCH */
1143  } /* WHILE */
1144 
1145  fclose (fdtask);
1146 
1147  // Compute the eMc matrix from the translations and rotations
1148  if (get_rot_eMc && get_trans_eMc) {
1149  for (unsigned int i=0; i < 3; i ++) {
1150  _erc[i] = rot_eMc[i];
1151  _etc[i] = trans_eMc[i];
1152  }
1153 
1154  vpRotationMatrix eRc(_erc);
1155  this->_eMc.buildFrom(_etc, eRc);
1156  }
1157 
1158  return;
1159 }
1160 #endif
1161 
1225 void
1227  const unsigned int &image_width,
1228  const unsigned int &image_height)
1229 {
1230 #if defined(VISP_HAVE_XML2) && defined (VISP_HAVE_ACCESS_TO_NAS)
1231  vpXmlParserCamera parser;
1232  switch (getToolType()) {
1233  case vpAfma6::TOOL_CCMOP: {
1234  std::cout << "Get camera parameters for camera \""
1235  << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl
1236  << "from the XML file: \""
1237  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1238  if (parser.parse(cam,
1241  projModel,
1242  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1244  "Impossible to read the camera parameters.");
1245  }
1246  break;
1247  }
1248  case vpAfma6::TOOL_GRIPPER: {
1249  std::cout << "Get camera parameters for camera \""
1250  << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl
1251  << "from the XML file: \""
1252  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1253  if (parser.parse(cam,
1256  projModel,
1257  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1259  "Impossible to read the camera parameters.");
1260  }
1261  break;
1262  }
1263  case vpAfma6::TOOL_VACUUM: {
1264  std::cout << "Get camera parameters for camera \""
1265  << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl
1266  << "from the XML file: \""
1267  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1268  if (parser.parse(cam,
1271  projModel,
1272  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1274  "Impossible to read the camera parameters.");
1275  }
1276  break;
1277  }
1279  std::cout << "Get camera parameters for camera \""
1280  << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
1281  << "from the XML file: \""
1282  << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\""<< std::endl;
1283  if (parser.parse(cam,
1286  projModel,
1287  image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1289  "Impossible to read the camera parameters.");
1290  }
1291  break;
1292  }
1293  default: {
1294  vpERROR_TRACE ("This error should not occur!");
1295  // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
1296  // "que les specs de la classe ont ete modifiee, "
1297  // "et que le code n'a pas ete mis a jour "
1298  // "correctement.");
1299  // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
1300  // "vpAfma6::vpAfma6ToolType, et controlez que "
1301  // "tous les cas ont ete pris en compte dans la "
1302  // "fonction init(camera).");
1304  "Impossible to read the camera parameters.");
1305  break;
1306  }
1307  }
1308 #else
1309  // Set default parameters
1310  switch (getToolType()) {
1311  case vpAfma6::TOOL_CCMOP: {
1312  // Set default intrinsic camera parameters for 640x480 images
1313  if (image_width == 640 && image_height == 480) {
1314  std::cout << "Get default camera parameters for camera \""
1315  << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl;
1316  switch(this->projModel) {
1318  cam.initPersProjWithoutDistortion(1108.0, 1110.0, 314.5, 243.2);
1319  break;
1321  cam.initPersProjWithDistortion(1090.6, 1090.0, 310.1, 260.8, -0.2114, 0.2217);
1322  break;
1323  }
1324  }
1325  else {
1326  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1328  "Impossible to read the camera parameters.");
1329  }
1330  break;
1331  }
1332  case vpAfma6::TOOL_GRIPPER: {
1333  // Set default intrinsic camera parameters for 640x480 images
1334  if (image_width == 640 && image_height == 480) {
1335  std::cout << "Get default camera parameters for camera \""
1336  << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl;
1337  switch(this->projModel) {
1339  cam.initPersProjWithoutDistortion(850.9, 853.0, 311.1, 243.6);
1340  break;
1342  cam.initPersProjWithDistortion(837.0, 837.5, 308.7, 251.6, -0.1455, 0.1511);
1343  break;
1344  }
1345  }
1346  else {
1347  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1349  "Impossible to read the camera parameters.");
1350  }
1351  break;
1352  }
1353  case vpAfma6::TOOL_VACUUM: {
1354  // Set default intrinsic camera parameters for 640x480 images
1355  if (image_width == 640 && image_height == 480) {
1356  std::cout << "Get default camera parameters for camera \""
1357  << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl;
1358  switch(this->projModel) {
1360  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1361  break;
1363  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1364  break;
1365  }
1366  }
1367  else {
1368  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1370  "Impossible to read the camera parameters.");
1371  }
1372  break;
1373  }
1375  // Set default intrinsic camera parameters for 640x480 images
1376  if (image_width == 640 && image_height == 480) {
1377  std::cout << "Get default camera parameters for camera \""
1378  << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl;
1379  switch(this->projModel) {
1381  cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1382  break;
1384  cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1385  break;
1386  }
1387  }
1388  else {
1389  vpTRACE("Cannot get default intrinsic camera parameters for this image resolution");
1391  "Impossible to read the camera parameters.");
1392  }
1393  break;
1394  }
1395  default:
1396  vpERROR_TRACE ("This error should not occur!");
1397  break;
1398  }
1399 #endif
1400  return;
1401 }
1402 
1444 void
1446  const vpImage<unsigned char> &I)
1447 {
1448  getCameraParameters(cam,I.getWidth(),I.getHeight());
1449 }
1493 void
1495  const vpImage<vpRGBa> &I)
1496 {
1497  getCameraParameters(cam,I.getWidth(),I.getHeight());
1498 }
1499 
1500 
1510 std::ostream & operator << (std::ostream & os,
1511  const vpAfma6 & afma6)
1512 {
1513  vpRotationMatrix eRc;
1514  afma6._eMc.extract(eRc);
1515  vpRxyzVector rxyz(eRc);
1516 
1517  os
1518  << "Joint Max:" << std::endl
1519  << "\t" << afma6._joint_max[0]
1520  << "\t" << afma6._joint_max[1]
1521  << "\t" << afma6._joint_max[2]
1522  << "\t" << afma6._joint_max[3]
1523  << "\t" << afma6._joint_max[4]
1524  << "\t" << afma6._joint_max[5]
1525  << "\t" << std::endl
1526 
1527  << "Joint Min: " << std::endl
1528  << "\t" << afma6._joint_min[0]
1529  << "\t" << afma6._joint_min[1]
1530  << "\t" << afma6._joint_min[2]
1531  << "\t" << afma6._joint_min[3]
1532  << "\t" << afma6._joint_min[4]
1533  << "\t" << afma6._joint_min[5]
1534  << "\t" << std::endl
1535 
1536  << "Long 5-6: " << std::endl
1537  << "\t" << afma6._long_56
1538  << "\t" << std::endl
1539 
1540  << "Coupling 5-6:" << std::endl
1541  << "\t" << afma6._coupl_56
1542  << "\t" << std::endl
1543 
1544  << "eMc: "<< std::endl
1545  << "\tTranslation (m): "
1546  << afma6._eMc[0][3] << " "
1547  << afma6._eMc[1][3] << " "
1548  << afma6._eMc[2][3]
1549  << "\t" << std::endl
1550  << "\tRotation Rxyz (rad) : "
1551  << rxyz[0] << " "
1552  << rxyz[1] << " "
1553  << rxyz[2]
1554  << "\t" << std::endl
1555  << "\tRotation Rxyz (deg) : "
1556  << vpMath::deg(rxyz[0]) << " "
1557  << vpMath::deg(rxyz[1]) << " "
1558  << vpMath::deg(rxyz[2])
1559  << "\t" << std::endl;
1560 
1561  return os;
1562 }
1563 /*
1564  * Local variables:
1565  * c-basic-offset: 2
1566  * End:
1567  */
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:154
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:860
void setIdentity()
Basic initialisation (identity)
vpHomogeneousMatrix get_fMc(const vpColVector &q)
Definition: vpAfma6.cpp:729
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
Definition: vpAfma6.cpp:1226
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:845
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:883
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static const char *const CONST_CAMERA_AFMA6_FILENAME
Definition: vpAfma6.h:85
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:1051
void extract(vpRotationMatrix &R) const
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe)
Definition: vpAfma6.cpp:791
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)
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true)
Definition: vpAfma6.cpp:555
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:987
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpAfma6.cpp:950
unsigned int getHeight() const
Definition: vpImage.h:145
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:1004
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:1019
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:1031
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