Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpAfma6.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * Interface for the Irisa's Afma6 robot.
32 */
33
41
42#include <iostream>
43#include <sstream>
44
45#include <visp3/core/vpCameraParameters.h>
46#include <visp3/core/vpDebug.h>
47#include <visp3/core/vpRotationMatrix.h>
48#include <visp3/core/vpRxyzVector.h>
49#include <visp3/core/vpTranslationVector.h>
50#include <visp3/core/vpVelocityTwistMatrix.h>
51#include <visp3/core/vpXmlParserCamera.h>
52#include <visp3/robot/vpAfma6.h>
53#include <visp3/robot/vpRobotException.h>
54
55/* ----------------------------------------------------------------------- */
56/* --- STATIC ------------------------------------------------------------ */
57/* ---------------------------------------------------------------------- */
58
60static const char *opt_Afma6[] = { "JOINT_MAX", "JOINT_MIN", "LONG_56", "COUPL_56",
61 "CAMERA", "eMc_ROT_XYZ", "eMc_TRANS_XYZ", nullptr };
62
63#ifdef VISP_HAVE_AFMA6_DATA
64const std::string vpAfma6::CONST_AFMA6_FILENAME =
65std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_Afma6.cnf");
66
68std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_without_distortion_Afma6.cnf");
69
71std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_ccmop_with_distortion_Afma6.cnf");
72
74std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_without_distortion_Afma6.cnf");
75
77std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_gripper_with_distortion_Afma6.cnf");
78
80std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_without_distortion_Afma6.cnf");
81
83std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_vacuum_with_distortion_Afma6.cnf");
84
86std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_without_distortion_Afma6.cnf");
87
89std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_generic_with_distortion_Afma6.cnf");
90
92std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_Intel_D435_without_distortion_Afma6.cnf");
93
95std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_eMc_Intel_D435_with_distortion_Afma6.cnf");
96
98std::string(VISP_AFMA6_DATA_PATH) + std::string("/include/const_camera_Afma6.xml");
99
100#endif // VISP_HAVE_AFMA6_DATA
101
102const char *const vpAfma6::CONST_CCMOP_CAMERA_NAME = "Dragonfly2-8mm-ccmop";
103const char *const vpAfma6::CONST_GRIPPER_CAMERA_NAME = "Dragonfly2-6mm-gripper";
104const char *const vpAfma6::CONST_VACUUM_CAMERA_NAME = "Dragonfly2-6mm-vacuum";
105const char *const vpAfma6::CONST_GENERIC_CAMERA_NAME = "Generic-camera";
106const char *const vpAfma6::CONST_INTEL_D435_CAMERA_NAME = "Intel-D435";
107
109
110const unsigned int vpAfma6::njoint = 6;
111
119 projModel(vpCameraParameters::perspectiveProjWithoutDistortion)
120{
121 // Set the default parameters in case of the config files are not available.
122
123 //
124 // Geometric model constant parameters
125 //
126 // coupling between join 5 and 6
127 this->_coupl_56 = 0.009091;
128 // distance between join 5 and 6
129 this->_long_56 = -0.06924;
130 // Camera extrinsic parameters: effector to camera frame
131 this->_eMc.eye(); // Default values are initialized ...
132 // ... in init (vpAfma6::vpAfma6ToolType tool,
133 // vpCameraParameters::vpCameraParametersProjType projModel)
134 // Maximal value of the joints
135 this->_joint_min[0] = -0.7501;
136 this->_joint_min[1] = -0.6501;
137 this->_joint_min[2] = -0.5001;
138 this->_joint_min[3] = -2.7301;
139 this->_joint_min[4] = -0.3001;
140 this->_joint_min[5] = -1.5901;
141 //_joint_max.resize(njoint);
142 this->_joint_max[0] = 0.6001;
143 this->_joint_max[1] = 0.6701;
144 this->_joint_max[2] = 0.4601;
145 this->_joint_max[3] = 2.7301;
146 this->_joint_max[4] = 2.4801;
147 this->_joint_max[5] = 1.5901;
148 init();
149}
150
156{
158 return;
159}
160
173void vpAfma6::init(const std::string &camera_extrinsic_parameters, const std::string &camera_intrinsic_parameters)
174{
175 this->parseConfigFile(camera_extrinsic_parameters);
176
177 this->parseConfigFile(camera_intrinsic_parameters);
178}
179
210void vpAfma6::init(vpAfma6::vpAfma6ToolType tool, const std::string &filename)
211{
212 this->setToolType(tool);
213 this->parseConfigFile(filename.c_str());
214}
215
225void vpAfma6::init(const std::string &camera_extrinsic_parameters)
226{
227 this->parseConfigFile(camera_extrinsic_parameters);
228}
229
246{
247 this->setToolType(tool);
248 this->set_eMc(eMc);
249}
250
269{
270
271 this->projModel = proj_model;
272
273#ifdef VISP_HAVE_AFMA6_DATA
274 // Read the robot parameters from files
275 std::string filename_eMc;
276 switch (tool) {
277 case vpAfma6::TOOL_CCMOP: {
278 switch (projModel) {
281 break;
284 break;
287 "Feature TOOL_CCMOP is not implemented for Kannala-Brandt projection model yet.");
288 break;
289 }
290 break;
291 }
293 switch (projModel) {
296 break;
299 break;
302 "Feature TOOL_GRIPPER is not implemented for Kannala-Brandt projection model yet.");
303 break;
304 }
305 break;
306 }
308 switch (projModel) {
311 break;
314 break;
317 "Feature TOOL_VACUUM is not implemented for Kannala-Brandt projection model yet.");
318 break;
319 }
320 break;
321 }
323 switch (projModel) {
326 break;
329 break;
332 "Feature TOOL_INTEL_D435_CAMERA is not implemented for Kannala-Brandt projection model yet.");
333 break;
334 }
335 break;
336 }
338 switch (projModel) {
341 break;
344 break;
347 "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
348 break;
349 }
350 break;
351 }
352 default: {
353 vpERROR_TRACE("This error should not occur!");
354 break;
355 }
356 }
357
358 this->init(vpAfma6::CONST_AFMA6_FILENAME, filename_eMc);
359
360#else // VISP_HAVE_AFMA6_DATA
361
362 // Use here default values of the robot constant parameters.
363 switch (tool) {
364 case vpAfma6::TOOL_CCMOP: {
365 switch (projModel) {
367 _erc[0] = vpMath::rad(164.35); // rx
368 _erc[1] = vpMath::rad(89.64); // ry
369 _erc[2] = vpMath::rad(-73.05); // rz
370 _etc[0] = 0.0117; // tx
371 _etc[1] = 0.0033; // ty
372 _etc[2] = 0.2272; // tz
373 break;
375 _erc[0] = vpMath::rad(33.54); // rx
376 _erc[1] = vpMath::rad(89.34); // ry
377 _erc[2] = vpMath::rad(57.83); // rz
378 _etc[0] = 0.0373; // tx
379 _etc[1] = 0.0024; // ty
380 _etc[2] = 0.2286; // tz
381 break;
384 "Feature TOOL_CCMOP is not implemented for Kannala-Brandt projection model yet.");
385 }
386 break;
387 }
389 switch (projModel) {
391 _erc[0] = vpMath::rad(88.33); // rx
392 _erc[1] = vpMath::rad(72.07); // ry
393 _erc[2] = vpMath::rad(2.53); // rz
394 _etc[0] = 0.0783; // tx
395 _etc[1] = 0.1234; // ty
396 _etc[2] = 0.1638; // tz
397 break;
399 _erc[0] = vpMath::rad(86.69); // rx
400 _erc[1] = vpMath::rad(71.93); // ry
401 _erc[2] = vpMath::rad(4.17); // rz
402 _etc[0] = 0.1034; // tx
403 _etc[1] = 0.1142; // ty
404 _etc[2] = 0.1642; // tz
405 break;
408 "Feature TOOL_GRIPPER is not implemented for Kannala-Brandt projection model yet.");
409 }
410 break;
411 }
413 switch (projModel) {
415 _erc[0] = vpMath::rad(90.40); // rx
416 _erc[1] = vpMath::rad(75.11); // ry
417 _erc[2] = vpMath::rad(0.18); // rz
418 _etc[0] = 0.0038; // tx
419 _etc[1] = 0.1281; // ty
420 _etc[2] = 0.1658; // tz
421 break;
423 _erc[0] = vpMath::rad(91.61); // rx
424 _erc[1] = vpMath::rad(76.17); // ry
425 _erc[2] = vpMath::rad(-0.98); // rz
426 _etc[0] = 0.0815; // tx
427 _etc[1] = 0.1162; // ty
428 _etc[2] = 0.1658; // tz
429 break;
432 "Feature TOOL_VACUUM is not implemented for Kannala-Brandt projection model yet.");
433 }
434 break;
435 }
437 switch (projModel) {
439 _erc[0] = vpMath::rad(-71.41); // rx
440 _erc[1] = vpMath::rad(89.49); // ry
441 _erc[2] = vpMath::rad(162.07); // rz
442 _etc[0] = 0.0038; // tx
443 _etc[1] = 0.1281; // ty
444 _etc[2] = 0.1658; // tz
445 break;
447 _erc[0] = vpMath::rad(-52.79); // rx
448 _erc[1] = vpMath::rad(89.55); // ry
449 _erc[2] = vpMath::rad(143.34); // rz
450 _etc[0] = 0.0693; // tx
451 _etc[1] = -0.0297; // ty
452 _etc[2] = 0.1357; // tz
453 break;
456 "Feature TOOL_INTEL_D435_CAMERA is not implemented for Kannala-Brandt projection model yet.");
457 }
458 break;
459 }
462 switch (projModel) {
465 // set eMc to identity
466 _erc[0] = 0; // rx
467 _erc[1] = 0; // ry
468 _erc[2] = 0; // rz
469 _etc[0] = 0; // tx
470 _etc[1] = 0; // ty
471 _etc[2] = 0; // tz
472 break;
475 "Feature TOOL_GENERIC_CAMERA is not implemented for Kannala-Brandt projection model yet.");
476 }
477 break;
478 }
479 }
481 this->_eMc.buildFrom(_etc, eRc);
482#endif // VISP_HAVE_AFMA6_DATA
483
484 setToolType(tool);
485 return;
486}
487
513{
515 fMc = get_fMc(q);
516
517 return fMc;
518}
519
596int vpAfma6::getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest,
597 const bool &verbose) const
598{
600 double q_[2][6], d[2], t;
601 int ok[2];
602 double cord[6];
603
604 int nbsol = 0;
605
606 if (q.getRows() != njoint)
607 q.resize(6);
608
609 // for(unsigned int i=0;i<3;i++) {
610 // fMe[i][3] = fMc[i][3];
611 // for(int j=0;j<3;j++) {
612 // fMe[i][j] = 0.0;
613 // for (int k=0;k<3;k++) fMe[i][j] += fMc[i][k]*rpi[j][k];
614 // fMe[i][3] -= fMe[i][j]*rpi[j][3];
615 // }
616 // }
617
618 // std::cout << "\n\nfMc: " << fMc;
619 // std::cout << "\n\neMc: " << _eMc;
620
621 fMe = fMc * this->_eMc.inverse();
622 // std::cout << "\n\nfMe: " << fMe;
623
624 if (fMe[2][2] >= .99999f) {
625 vpTRACE("singularity\n");
626 q_[0][4] = q_[1][4] = M_PI / 2.f;
627 t = atan2(fMe[0][0], fMe[0][1]);
628 q_[1][3] = q_[0][3] = q[3];
629 q_[1][5] = q_[0][5] = t - q_[0][3];
630
631 while ((q_[1][5] + vpMath::rad(2)) >= this->_joint_max[5])
632 /* -> a cause du couplage 4/5 */
633 {
634 q_[1][5] -= vpMath::rad(10);
635 q_[1][3] += vpMath::rad(10);
636 }
637 while (q_[1][5] <= this->_joint_min[5]) {
638 q_[1][5] += vpMath::rad(10);
639 q_[1][3] -= vpMath::rad(10);
640 }
641 }
642 else if (fMe[2][2] <= -.99999) {
643 vpTRACE("singularity\n");
644 q_[0][4] = q_[1][4] = -M_PI / 2;
645 t = atan2(fMe[1][1], fMe[1][0]);
646 q_[1][3] = q_[0][3] = q[3];
647 q_[1][5] = q_[0][5] = q_[0][3] - t;
648 while ((q_[1][5] + vpMath::rad(2)) >= this->_joint_max[5])
649 /* -> a cause du couplage 4/5 */
650 {
651 q_[1][5] -= vpMath::rad(10);
652 q_[1][3] -= vpMath::rad(10);
653 }
654 while (q_[1][5] <= this->_joint_min[5]) {
655 q_[1][5] += vpMath::rad(10);
656 q_[1][3] += vpMath::rad(10);
657 }
658 }
659 else {
660 q_[0][3] = atan2(-fMe[0][2], fMe[1][2]);
661 if (q_[0][3] >= 0.0)
662 q_[1][3] = q_[0][3] - M_PI;
663 else
664 q_[1][3] = q_[0][3] + M_PI;
665
666 q_[0][4] = asin(fMe[2][2]);
667 if (q_[0][4] >= 0.0)
668 q_[1][4] = M_PI - q_[0][4];
669 else
670 q_[1][4] = -M_PI - q_[0][4];
671
672 q_[0][5] = atan2(-fMe[2][1], fMe[2][0]);
673 if (q_[0][5] >= 0.0)
674 q_[1][5] = q_[0][5] - M_PI;
675 else
676 q_[1][5] = q_[0][5] + M_PI;
677 }
678 q_[0][0] = fMe[0][3] - this->_long_56 * cos(q_[0][3]);
679 q_[1][0] = fMe[0][3] - this->_long_56 * cos(q_[1][3]);
680 q_[0][1] = fMe[1][3] - this->_long_56 * sin(q_[0][3]);
681 q_[1][1] = fMe[1][3] - this->_long_56 * sin(q_[1][3]);
682 q_[0][2] = q_[1][2] = fMe[2][3];
683
684 /* prise en compte du couplage axes 5/6 */
685 q_[0][5] += this->_coupl_56 * q_[0][4];
686 q_[1][5] += this->_coupl_56 * q_[1][4];
687
688 for (int j = 0; j < 2; j++) {
689 ok[j] = 1;
690 // test is position is reachable
691 for (unsigned int i = 0; i < 6; i++) {
692 if (q_[j][i] < this->_joint_min[i] || q_[j][i] > this->_joint_max[i]) {
693 if (verbose) {
694 if (i < 3)
695 std::cout << "Joint " << i << " not in limits: " << this->_joint_min[i] << " < " << q_[j][i] << " < "
696 << this->_joint_max[i] << std::endl;
697 else
698 std::cout << "Joint " << i << " not in limits: " << vpMath::deg(this->_joint_min[i]) << " < "
699 << vpMath::deg(q_[j][i]) << " < " << vpMath::deg(this->_joint_max[i]) << std::endl;
700 }
701 ok[j] = 0;
702 }
703 }
704 }
705 if (ok[0] == 0) {
706 if (ok[1] == 0) {
707 std::cout << "No solution..." << std::endl;
708 nbsol = 0;
709 return nbsol;
710 }
711 else if (ok[1] == 1) {
712 for (unsigned int i = 0; i < 6; i++)
713 cord[i] = q_[1][i];
714 nbsol = 1;
715 }
716 }
717 else {
718 if (ok[1] == 0) {
719 for (unsigned int i = 0; i < 6; i++)
720 cord[i] = q_[0][i];
721 nbsol = 1;
722 }
723 else {
724 nbsol = 2;
725 // vpTRACE("2 solutions\n");
726 for (int j = 0; j < 2; j++) {
727 d[j] = 0.0;
728 for (unsigned int i = 3; i < 6; i++)
729 d[j] += (q_[j][i] - q[i]) * (q_[j][i] - q[i]);
730 }
731 if (nearest == true) {
732 if (d[0] <= d[1])
733 for (unsigned int i = 0; i < 6; i++)
734 cord[i] = q_[0][i];
735 else
736 for (unsigned int i = 0; i < 6; i++)
737 cord[i] = q_[1][i];
738 }
739 else {
740 if (d[0] <= d[1])
741 for (unsigned int i = 0; i < 6; i++)
742 cord[i] = q_[1][i];
743 else
744 for (unsigned int i = 0; i < 6; i++)
745 cord[i] = q_[0][i];
746 }
747 }
748 }
749 for (unsigned int i = 0; i < 6; i++)
750 q[i] = cord[i];
751
752 return nbsol;
753}
754
778{
780 get_fMc(q, fMc);
781
782 return fMc;
783}
784
805{
806
807 // Compute the direct geometric model: fMe = transformation between
808 // fix and end effector frame.
810
811 get_fMe(q, fMe);
812
813 fMc = fMe * this->_eMc;
814
815 return;
816}
817
838{
839 double q0 = q[0]; // meter
840 double q1 = q[1]; // meter
841 double q2 = q[2]; // meter
842
843 /* Decouplage liaisons 2 et 3. */
844 double q5 = q[5] - this->_coupl_56 * q[4];
845
846 double c1 = cos(q[3]);
847 double s1 = sin(q[3]);
848 double c2 = cos(q[4]);
849 double s2 = sin(q[4]);
850 double c3 = cos(q5);
851 double s3 = sin(q5);
852
853 // Compute the direct geometric model: fMe = transformation betwee
854 // fix and end effector frame.
855 fMe[0][0] = s1 * s2 * c3 + c1 * s3;
856 fMe[0][1] = -s1 * s2 * s3 + c1 * c3;
857 fMe[0][2] = -s1 * c2;
858 fMe[0][3] = q0 + this->_long_56 * c1;
859
860 fMe[1][0] = -c1 * s2 * c3 + s1 * s3;
861 fMe[1][1] = c1 * s2 * s3 + s1 * c3;
862 fMe[1][2] = c1 * c2;
863 fMe[1][3] = q1 + this->_long_56 * s1;
864
865 fMe[2][0] = c2 * c3;
866 fMe[2][1] = -c2 * s3;
867 fMe[2][2] = s2;
868 fMe[2][3] = q2;
869
870 fMe[3][0] = 0;
871 fMe[3][1] = 0;
872 fMe[3][2] = 0;
873 fMe[3][3] = 1;
874
875 // vpCTRACE << "Effector position fMe: " << std::endl << fMe;
876
877 return;
878}
879
890void vpAfma6::get_cMe(vpHomogeneousMatrix &cMe) const { cMe = this->_eMc.inverse(); }
901vpHomogeneousMatrix vpAfma6::get_eMc() const { return (this->_eMc); }
902
913{
915 get_cMe(cMe);
916
917 cVe.buildFrom(cMe);
918
919 return;
920}
921
934void vpAfma6::get_eJe(const vpColVector &q, vpMatrix &eJe) const
935{
936
937 eJe.resize(6, 6);
938
939 double s4, c4, s5, c5, s6, c6;
940
941 s4 = sin(q[3]);
942 c4 = cos(q[3]);
943 s5 = sin(q[4]);
944 c5 = cos(q[4]);
945 s6 = sin(q[5] - this->_coupl_56 * q[4]);
946 c6 = cos(q[5] - this->_coupl_56 * q[4]);
947
948 eJe = 0;
949 eJe[0][0] = s4 * s5 * c6 + c4 * s6;
950 eJe[0][1] = -c4 * s5 * c6 + s4 * s6;
951 eJe[0][2] = c5 * c6;
952 eJe[0][3] = -this->_long_56 * s5 * c6;
953
954 eJe[1][0] = -s4 * s5 * s6 + c4 * c6;
955 eJe[1][1] = c4 * s5 * s6 + s4 * c6;
956 eJe[1][2] = -c5 * s6;
957 eJe[1][3] = this->_long_56 * s5 * s6;
958
959 eJe[2][0] = -s4 * c5;
960 eJe[2][1] = c4 * c5;
961 eJe[2][2] = s5;
962 eJe[2][3] = this->_long_56 * c5;
963
964 eJe[3][3] = c5 * c6;
965 eJe[3][4] = s6;
966
967 eJe[4][3] = -c5 * s6;
968 eJe[4][4] = c6;
969
970 eJe[5][3] = s5;
971 eJe[5][4] = -this->_coupl_56;
972 eJe[5][5] = 1;
973
974 return;
975}
976
1003
1004void vpAfma6::get_fJe(const vpColVector &q, vpMatrix &fJe) const
1005{
1006
1007 fJe.resize(6, 6);
1008
1009 // block superieur gauche
1010 fJe[0][0] = fJe[1][1] = fJe[2][2] = 1;
1011
1012 double s4 = sin(q[3]);
1013 double c4 = cos(q[3]);
1014
1015 // block superieur droit
1016 fJe[0][3] = -this->_long_56 * s4;
1017 fJe[1][3] = this->_long_56 * c4;
1018
1019 double s5 = sin(q[4]);
1020 double c5 = cos(q[4]);
1021 // block inferieur droit
1022 fJe[3][4] = c4;
1023 fJe[3][5] = -s4 * c5;
1024 fJe[4][4] = s4;
1025 fJe[4][5] = c4 * c5;
1026 fJe[5][3] = 1;
1027 fJe[5][5] = s5;
1028
1029 // coupling between joint 5 and 6
1030 fJe[3][4] += this->_coupl_56 * s4 * c5;
1031 fJe[4][4] += -this->_coupl_56 * c4 * c5;
1032 fJe[5][4] += -this->_coupl_56 * s5;
1033
1034 return;
1035}
1036
1046{
1047 vpColVector qmin(6);
1048 for (unsigned int i = 0; i < 6; i++)
1049 qmin[i] = this->_joint_min[i];
1050 return qmin;
1051}
1052
1062{
1063 vpColVector qmax(6);
1064 for (unsigned int i = 0; i < 6; i++)
1065 qmax[i] = this->_joint_max[i];
1066 return qmax;
1067}
1068
1075double vpAfma6::getCoupl56() const { return _coupl_56; }
1076
1083double vpAfma6::getLong56() const { return _long_56; }
1084
1095void vpAfma6::parseConfigFile(const std::string &filename)
1096{
1097 vpRxyzVector erc; // eMc rotation
1098 vpTranslationVector etc; // eMc translation
1099
1100 std::ifstream fdconfig(filename.c_str(), std::ios::in);
1101
1102 if (!fdconfig.is_open()) {
1103 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the config file: %s",
1104 filename.c_str());
1105 }
1106
1107 std::string line;
1108 int lineNum = 0;
1109 bool get_erc = false;
1110 bool get_etc = false;
1111 int code;
1112
1113 while (std::getline(fdconfig, line)) {
1114 lineNum++;
1115 if ((line.compare(0, 1, "#") == 0) || line.empty()) { // skip comment or empty line
1116 continue;
1117 }
1118 std::istringstream ss(line);
1119 std::string key;
1120 ss >> key;
1121
1122 for (code = 0; nullptr != opt_Afma6[code]; ++code) {
1123 if (key.compare(opt_Afma6[code]) == 0) {
1124 break;
1125 }
1126 }
1127
1128 switch (code) {
1129 case 0:
1130 ss >> this->_joint_max[0] >> this->_joint_max[1] >> this->_joint_max[2] >> this->_joint_max[3] >>
1131 this->_joint_max[4] >> this->_joint_max[5];
1132 break;
1133
1134 case 1:
1135 ss >> this->_joint_min[0] >> this->_joint_min[1] >> this->_joint_min[2] >> this->_joint_min[3] >>
1136 this->_joint_min[4] >> this->_joint_min[5];
1137 break;
1138
1139 case 2:
1140 ss >> this->_long_56;
1141 break;
1142
1143 case 3:
1144 ss >> this->_coupl_56;
1145 break;
1146
1147 case 4:
1148 break; // Nothing to do: camera name
1149
1150 case 5:
1151 ss >> erc[0] >> erc[1] >> erc[2];
1152
1153 // Convert rotation from degrees to radians
1154 erc = erc * M_PI / 180.0;
1155 get_erc = true;
1156 break;
1157
1158 case 6:
1159 ss >> etc[0] >> etc[1] >> etc[2];
1160 get_etc = true;
1161 break;
1162
1163 default:
1164 throw(vpRobotException(vpRobotException::readingParametersError, "Bad configuration file %s line #%d",
1165 filename.c_str(), lineNum));
1166 }
1167 }
1168
1169 fdconfig.close();
1170
1171 // Compute the eMc matrix from the translations and rotations
1172 if (get_etc && get_erc) {
1173 _erc = erc;
1174 _etc = etc;
1175
1177 this->_eMc.buildFrom(_etc, eRc);
1178 }
1179}
1180
1190{
1191 this->_eMc = eMc;
1192 this->_etc = eMc.getTranslationVector();
1193
1194 vpRotationMatrix R(eMc);
1195 this->_erc.buildFrom(R);
1196}
1197
1261
1262void vpAfma6::getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width,
1263 const unsigned int &image_height) const
1264{
1265#if defined(VISP_HAVE_AFMA6_DATA) && defined(VISP_HAVE_PUGIXML)
1266 vpXmlParserCamera parser;
1267 switch (getToolType()) {
1268 case vpAfma6::TOOL_CCMOP: {
1269 std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\"" << std::endl
1270 << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1272 image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1273 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1274 }
1275 break;
1276 }
1277 case vpAfma6::TOOL_GRIPPER: {
1278 std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\"" << std::endl
1279 << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1281 image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1282 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1283 }
1284 break;
1285 }
1286 case vpAfma6::TOOL_VACUUM: {
1287 std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\"" << std::endl
1288 << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1290 image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1291 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1292 }
1293 break;
1294 }
1296 std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_INTEL_D435_CAMERA_NAME << "\"" << std::endl
1297 << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1299 image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1300 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1301 }
1302 break;
1303 }
1305 std::cout << "Get camera parameters for camera \"" << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\"" << std::endl
1306 << "from the XML file: \"" << vpAfma6::CONST_CAMERA_AFMA6_FILENAME << "\"" << std::endl;
1308 image_width, image_height) != vpXmlParserCamera::SEQUENCE_OK) {
1309 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1310 }
1311 break;
1312 }
1313 default: {
1314 vpERROR_TRACE("This error should not occur!");
1315 // vpERROR_TRACE ("Si elle survient malgre tout, c'est sans doute "
1316 // "que les specs de la classe ont ete modifiee, "
1317 // "et que le code n'a pas ete mis a jour "
1318 // "correctement.");
1319 // vpERROR_TRACE ("Verifiez les valeurs possibles du type "
1320 // "vpAfma6::vpAfma6ToolType, et controlez que "
1321 // "tous les cas ont ete pris en compte dans la "
1322 // "fonction init(camera).");
1323 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1324 }
1325 }
1326#else
1327 // Set default parameters
1328 switch (getToolType()) {
1329 case vpAfma6::TOOL_CCMOP: {
1330 // Set default intrinsic camera parameters for 640x480 images
1331 if (image_width == 640 && image_height == 480) {
1332 std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\""
1333 << std::endl;
1334 switch (this->projModel) {
1336 cam.initPersProjWithoutDistortion(1108.0, 1110.0, 314.5, 243.2);
1337 break;
1339 cam.initPersProjWithDistortion(1090.6, 1090.0, 310.1, 260.8, -0.2114, 0.2217);
1340 break;
1343 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1344 }
1345 }
1346 else {
1347 vpTRACE("Cannot get default intrinsic camera parameters for this image "
1348 "resolution");
1349 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1350 }
1351 break;
1352 }
1353 case vpAfma6::TOOL_GRIPPER: {
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 \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\""
1357 << std::endl;
1358 switch (this->projModel) {
1360 cam.initPersProjWithoutDistortion(850.9, 853.0, 311.1, 243.6);
1361 break;
1363 cam.initPersProjWithDistortion(837.0, 837.5, 308.7, 251.6, -0.1455, 0.1511);
1364 break;
1367 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1368 }
1369 }
1370 else {
1371 vpTRACE("Cannot get default intrinsic camera parameters for this image "
1372 "resolution");
1373 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1374 }
1375 break;
1376 }
1377 case vpAfma6::TOOL_VACUUM: {
1378 // Set default intrinsic camera parameters for 640x480 images
1379 if (image_width == 640 && image_height == 480) {
1380 std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_VACUUM_CAMERA_NAME << "\""
1381 << std::endl;
1382 switch (this->projModel) {
1384 cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1385 break;
1387 cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1388 break;
1391 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1392 }
1393 }
1394 else {
1395 vpTRACE("Cannot get default intrinsic camera parameters for this image "
1396 "resolution");
1397 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1398 }
1399 break;
1400 }
1402 // Set default intrinsic camera parameters for 640x480 images
1403 if (image_width == 640 && image_height == 480) {
1404 std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_INTEL_D435_CAMERA_NAME << "\""
1405 << std::endl;
1406 switch (this->projModel) {
1408 cam.initPersProjWithoutDistortion(605.4, 605.6, 328.6, 241.0);
1409 break;
1411 cam.initPersProjWithDistortion(611.8, 612.6, 327.8, 241.7, 0.0436, -0.04265);
1412 break;
1415 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1416 }
1417 }
1418 else {
1419 vpTRACE("Cannot get default intrinsic camera parameters for this image "
1420 "resolution");
1421 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1422 }
1423 break;
1424 }
1426 // Set default intrinsic camera parameters for 640x480 images
1427 if (image_width == 640 && image_height == 480) {
1428 std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GENERIC_CAMERA_NAME << "\""
1429 << std::endl;
1430 switch (this->projModel) {
1432 cam.initPersProjWithoutDistortion(853.5, 856.0, 307.8, 236.8);
1433 break;
1435 cam.initPersProjWithDistortion(828.5, 829.0, 322.5, 232.9, -0.1921, 0.2057);
1436 break;
1439 "Feature getCameraParameters is not implemented for Kannala-Brandt projection model yet.");
1440 }
1441 }
1442 else {
1443 vpTRACE("Cannot get default intrinsic camera parameters for this image "
1444 "resolution");
1445 throw vpRobotException(vpRobotException::readingParametersError, "Impossible to read the camera parameters.");
1446 }
1447 break;
1448 }
1449 default:
1450 vpERROR_TRACE("This error should not occur!");
1451 break;
1452 }
1453#endif
1454 return;
1455}
1456
1504{
1505 getCameraParameters(cam, I.getWidth(), I.getHeight());
1506}
1507
1553
1555{
1556 getCameraParameters(cam, I.getWidth(), I.getHeight());
1557}
1558
1568VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAfma6 &afma6)
1569{
1570 vpRotationMatrix eRc;
1571 afma6._eMc.extract(eRc);
1572 vpRxyzVector rxyz(eRc);
1573
1574 os << "Joint Max:" << std::endl
1575 << "\t" << afma6._joint_max[0] << "\t" << afma6._joint_max[1] << "\t" << afma6._joint_max[2] << "\t"
1576 << afma6._joint_max[3] << "\t" << afma6._joint_max[4] << "\t" << afma6._joint_max[5] << "\t" << std::endl
1577
1578 << "Joint Min: " << std::endl
1579 << "\t" << afma6._joint_min[0] << "\t" << afma6._joint_min[1] << "\t" << afma6._joint_min[2] << "\t"
1580 << afma6._joint_min[3] << "\t" << afma6._joint_min[4] << "\t" << afma6._joint_min[5] << "\t" << std::endl
1581
1582 << "Long 5-6: " << std::endl
1583 << "\t" << afma6._long_56 << "\t" << std::endl
1584
1585 << "Coupling 5-6:" << std::endl
1586 << "\t" << afma6._coupl_56 << "\t" << std::endl
1587
1588 << "eMc: " << std::endl
1589 << "\tTranslation (m): " << afma6._eMc[0][3] << " " << afma6._eMc[1][3] << " " << afma6._eMc[2][3] << "\t"
1590 << std::endl
1591 << "\tRotation Rxyz (rad) : " << rxyz[0] << " " << rxyz[1] << " " << rxyz[2] << "\t" << std::endl
1592 << "\tRotation Rxyz (deg) : " << vpMath::deg(rxyz[0]) << " " << vpMath::deg(rxyz[1]) << " " << vpMath::deg(rxyz[2])
1593 << "\t" << std::endl;
1594
1595 return os;
1596}
1597END_VISP_NAMESPACE
static const std::string CONST_EMC_GENERIC_WITHOUT_DISTORTION_FILENAME
Definition vpAfma6.h:91
static const char *const CONST_CCMOP_CAMERA_NAME
Definition vpAfma6.h:99
static const std::string CONST_EMC_CCMOP_WITH_DISTORTION_FILENAME
Definition vpAfma6.h:84
friend VISP_EXPORT std::ostream & operator<<(std::ostream &os, const vpAfma6 &afma6)
Definition vpAfma6.cpp:1568
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
Definition vpAfma6.cpp:1189
static const std::string CONST_EMC_CCMOP_WITHOUT_DISTORTION_FILENAME
Definition vpAfma6.h:83
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition vpAfma6.cpp:912
static const std::string CONST_EMC_INTEL_D435_WITHOUT_DISTORTION_FILENAME
Definition vpAfma6.h:89
vpColVector getJointMax() const
Definition vpAfma6.cpp:1061
static const std::string CONST_CAMERA_AFMA6_FILENAME
Definition vpAfma6.h:93
double _joint_min[6]
Definition vpAfma6.h:202
vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const
Definition vpAfma6.cpp:512
static const unsigned int njoint
Number of joint.
Definition vpAfma6.h:196
void init(void)
Definition vpAfma6.cpp:155
vpRxyzVector _erc
Definition vpAfma6.h:205
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition vpAfma6.cpp:596
static const char *const CONST_VACUUM_CAMERA_NAME
Definition vpAfma6.h:109
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition vpAfma6.cpp:837
static const std::string CONST_EMC_GRIPPER_WITHOUT_DISTORTION_FILENAME
Definition vpAfma6.h:85
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition vpAfma6.cpp:890
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition vpAfma6.h:192
vpAfma6ToolType getToolType() const
Get the current tool type.
Definition vpAfma6.h:167
double _coupl_56
Definition vpAfma6.h:199
static const std::string CONST_EMC_INTEL_D435_WITH_DISTORTION_FILENAME
Definition vpAfma6.h:90
vpColVector getJointMin() const
Definition vpAfma6.cpp:1045
static const char *const CONST_INTEL_D435_CAMERA_NAME
Definition vpAfma6.h:120
double getCoupl56() const
Definition vpAfma6.cpp:1075
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition vpAfma6.h:134
static const char *const CONST_GRIPPER_CAMERA_NAME
Definition vpAfma6.h:104
static const std::string CONST_EMC_GRIPPER_WITH_DISTORTION_FILENAME
Definition vpAfma6.h:86
vpHomogeneousMatrix _eMc
Definition vpAfma6.h:207
double _long_56
Definition vpAfma6.h:200
void parseConfigFile(const std::string &filename)
Definition vpAfma6.cpp:1095
vpTranslationVector _etc
Definition vpAfma6.h:204
vpHomogeneousMatrix get_eMc() const
Definition vpAfma6.cpp:901
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition vpAfma6.cpp:1262
vpAfma6ToolType tool_current
Current tool in use.
Definition vpAfma6.h:211
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition vpAfma6.cpp:777
static const char *const CONST_GENERIC_CAMERA_NAME
Definition vpAfma6.h:114
vpCameraParameters::vpCameraParametersProjType projModel
Definition vpAfma6.h:213
static const std::string CONST_EMC_VACUUM_WITHOUT_DISTORTION_FILENAME
Definition vpAfma6.h:87
static const std::string CONST_EMC_GENERIC_WITH_DISTORTION_FILENAME
Definition vpAfma6.h:92
double _joint_max[6]
Definition vpAfma6.h:201
static const std::string CONST_EMC_VACUUM_WITH_DISTORTION_FILENAME
Definition vpAfma6.h:88
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition vpAfma6.cpp:934
static const std::string CONST_AFMA6_FILENAME
Definition vpAfma6.h:82
double getLong56() const
Definition vpAfma6.cpp:1083
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition vpAfma6.cpp:1004
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition vpAfma6.h:124
@ TOOL_CCMOP
Definition vpAfma6.h:125
@ TOOL_GENERIC_CAMERA
Definition vpAfma6.h:128
@ TOOL_CUSTOM
Definition vpAfma6.h:130
@ TOOL_VACUUM
Definition vpAfma6.h:127
@ TOOL_INTEL_D435_CAMERA
Definition vpAfma6.h:129
@ TOOL_GRIPPER
Definition vpAfma6.h:126
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
Definition vpArray2D.h:448
unsigned int getRows() const
Definition vpArray2D.h:433
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ ProjWithKannalaBrandtDistortion
Projection with Kannala-Brandt distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
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.
vpTranslationVector getTranslationVector() const
void extract(vpRotationMatrix &R) const
Definition of the vpImage class member functions.
Definition vpImage.h:131
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:175
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.
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
XML parser to load and save intrinsic camera parameters.
#define vpTRACE
Definition vpDebug.h:450
#define vpERROR_TRACE
Definition vpDebug.h:423