Visual Servoing Platform  version 3.6.1 under development (2024-05-08)
calibrate-hand-eye.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Hand-eye calibration example to estimate hand to eye transformation.
33  *
34 *****************************************************************************/
35 
43 #include <iomanip>
44 #include <sstream>
45 #include <stdio.h>
46 #include <vector>
47 
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpExponentialMap.h>
50 #include <visp3/core/vpIoTools.h>
51 #include <visp3/io/vpParseArgv.h>
52 #include <visp3/vision/vpHandEyeCalibration.h>
53 
54 int main()
55 {
56 #if (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV))
57  try {
58  // We want to calibrate the hand-eye extrinsic camera parameters from 6
59  // couple of poses: cMo and wMe
60  const unsigned int N = 6;
61  // Input: six couple of poses used as input in the calibration proces
62  std::vector<vpHomogeneousMatrix> cMo(N); // eye (camera) to object
63  // transformation. The object
64  // frame is attached to the
65  // calibrartion grid
66  std::vector<vpHomogeneousMatrix> wMe(N); // world to hand (end-effector) transformation
67  // Output: Result of the calibration
68  vpHomogeneousMatrix eMc; // hand (end-effector) to eye (camera) transformation
69 
70  // Initialize an eMc transformation used to produce the simulated input
71  // transformations cMo and wMe
72  vpTranslationVector etc(0.1, 0.2, 0.3);
73  vpThetaUVector erc;
74  erc[0] = vpMath::rad(10); // 10 deg
75  erc[1] = vpMath::rad(-10); // -10 deg
76  erc[2] = vpMath::rad(25); // 25 deg
77 
78  eMc.buildFrom(etc, erc);
79  std::cout << "Simulated hand-eye transformation: eMc " << std::endl;
80  std::cout << eMc << std::endl;
81  std::cout << "Theta U rotation: " << vpMath::deg(erc[0]) << " " << vpMath::deg(erc[1]) << " " << vpMath::deg(erc[2])
82  << std::endl;
83 
84  vpColVector v_c(6); // camera velocity used to produce 6 simulated poses
85  for (unsigned int i = 0; i < N; i++) {
86  v_c = 0;
87  if (i == 0) {
88  // Initialize first poses
89  cMo[0].buildFrom(0, 0, 0.5, 0, 0, 0); // z=0.5 m
90  wMe[0].buildFrom(0, 0, 0, 0, 0, 0); // Id
91  }
92  else if (i == 1)
93  v_c[3] = M_PI / 8;
94  else if (i == 2)
95  v_c[4] = M_PI / 8;
96  else if (i == 3)
97  v_c[5] = M_PI / 10;
98  else if (i == 4)
99  v_c[0] = 0.5;
100  else if (i == 5)
101  v_c[1] = 0.8;
102 
103  vpHomogeneousMatrix cMc; // camera displacement
104  cMc = vpExponentialMap::direct(v_c); // Compute the camera displacement
105  // due to the velocity applied to
106  // the camera
107  if (i > 0) {
108  // From the camera displacement cMc, compute the wMe and cMo matrices
109  cMo[i] = cMc.inverse() * cMo[i - 1];
110  wMe[i] = wMe[i - 1] * eMc * cMc * eMc.inverse();
111  }
112  }
113 
114  // if (1) {
115  if (1) {
116  for (unsigned int i = 0; i < N; i++) {
118  wMo = wMe[i] * eMc * cMo[i];
119  std::cout << std::endl << "wMo[" << i << "] " << std::endl;
120  std::cout << wMo << std::endl;
121  std::cout << "cMo[" << i << "] " << std::endl;
122  std::cout << cMo[i] << std::endl;
123  std::cout << "wMe[" << i << "] " << std::endl;
124  std::cout << wMe[i] << std::endl;
125  }
126  }
127 
128  // Reset the eMc matrix to eye
129  eMc.eye();
130 
131  // Compute the eMc hand to eye transformation from six poses
132  // - cMo[6]: camera to object poses as six homogeneous transformations
133  // - wMe[6]: world to hand (end-effector) poses as six homogeneous
134  // transformations
135  int ret = vpHandEyeCalibration::calibrate(cMo, wMe, eMc);
136 
137  if (ret == 0) {
138  std::cout << std::endl << "** Hand-eye calibration succeed" << std::endl;
139  std::cout << std::endl << "** Hand-eye (eMc) transformation estimated:" << std::endl;
140  std::cout << eMc << std::endl;
141  std::cout << "** Corresponding pose vector: " << vpPoseVector(eMc).t() << std::endl;
142  eMc.extract(erc);
143  std::cout << std::endl
144  << "** Translation [m]: " << eMc[0][3] << " " << eMc[1][3] << " " << eMc[2][3] << std::endl;
145  std::cout << "** Rotation (theta-u representation) [rad]: " << erc.t() << std::endl;
146  std::cout << "** Rotation (theta-u representation) [deg]: " << vpMath::deg(erc[0]) << " " << vpMath::deg(erc[1])
147  << " " << vpMath::deg(erc[2]) << std::endl;
148  vpQuaternionVector quaternion(eMc.getRotationMatrix());
149  std::cout << "** Rotation (quaternion representation) [rad]: " << quaternion.t() << std::endl;
150  }
151  else {
152  std::cout << std::endl << "** Hand-eye calibration failed" << std::endl;
153  std::cout << std::endl
154  << "Check your input data and ensure they are covering the half sphere over the chessboard."
155  << std::endl;
156  std::cout << std::endl
157  << "See https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-calibration-extrinsic.html" << std::endl;
158  }
159 
160  return EXIT_SUCCESS;
161  }
162  catch (const vpException &e) {
163  std::cout << "Catch an exception: " << e << std::endl;
164  return EXIT_FAILURE;
165  }
166 #else
167  std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl;
168  return EXIT_SUCCESS;
169 #endif
170 }
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
error that can be emitted by ViSP classes.
Definition: vpException.h:59
static vpHomogeneousMatrix direct(const vpColVector &v)
static int calibrate(const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpRotationMatrix getRotationMatrix() const
vpHomogeneousMatrix inverse() const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void extract(vpRotationMatrix &R) const
static double rad(double deg)
Definition: vpMath.h:127
static double deg(double rad)
Definition: vpMath.h:117
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:189
vpRowVector t() const
Implementation of a rotation vector as quaternion angle minimal representation.
vpRowVector t() const
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.