Visual Servoing Platform  version 3.4.0
calibrate-hand-eye.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 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 http://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  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
46 #include <iomanip>
47 #include <sstream>
48 #include <stdio.h>
49 #include <vector>
50 
51 #include <visp3/core/vpDebug.h>
52 #include <visp3/core/vpExponentialMap.h>
53 #include <visp3/core/vpIoTools.h>
54 #include <visp3/io/vpParseArgv.h>
55 #include <visp3/vision/vpHandEyeCalibration.h>
56 
57 int main()
58 {
59 #if (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV))
60  try {
61  // We want to calibrate the hand-eye extrinsic camera parameters from 6
62  // couple of poses: cMo and wMe
63  const unsigned int N = 6;
64  // Input: six couple of poses used as input in the calibration proces
65  std::vector<vpHomogeneousMatrix> cMo(N); // eye (camera) to object
66  // transformation. The object
67  // frame is attached to the
68  // calibrartion grid
69  std::vector<vpHomogeneousMatrix> wMe(N); // world to hand (end-effector) transformation
70  // Output: Result of the calibration
71  vpHomogeneousMatrix eMc; // hand (end-effector) to eye (camera) transformation
72 
73  // Initialize an eMc transformation used to produce the simulated input
74  // transformations cMo and wMe
75  vpTranslationVector etc(0.1, 0.2, 0.3);
76  vpThetaUVector erc;
77  erc[0] = vpMath::rad(10); // 10 deg
78  erc[1] = vpMath::rad(-10); // -10 deg
79  erc[2] = vpMath::rad(25); // 25 deg
80 
81  eMc.buildFrom(etc, erc);
82  std::cout << "Simulated hand-eye transformation: eMc " << std::endl;
83  std::cout << eMc << std::endl;
84  std::cout << "Theta U rotation: " << vpMath::deg(erc[0]) << " " << vpMath::deg(erc[1]) << " " << vpMath::deg(erc[2])
85  << std::endl;
86 
87  vpColVector v_c(6); // camera velocity used to produce 6 simulated poses
88  for (unsigned int i = 0; i < N; i++) {
89  v_c = 0;
90  if (i == 0) {
91  // Initialize first poses
92  cMo[0].buildFrom(0, 0, 0.5, 0, 0, 0); // z=0.5 m
93  wMe[0].buildFrom(0, 0, 0, 0, 0, 0); // Id
94  } else if (i == 1)
95  v_c[3] = M_PI/8 ;
96  else if (i == 2)
97  v_c[4] = M_PI/8 ;
98  else if (i == 3)
99  v_c[5] = M_PI/10 ;
100  else if (i == 4)
101  v_c[0] = 0.5;
102  else if (i == 5)
103  v_c[1] = 0.8;
104 
105  vpHomogeneousMatrix cMc; // camera displacement
106  cMc = vpExponentialMap::direct(v_c); // Compute the camera displacement
107  // due to the velocity applied to
108  // the camera
109  if (i > 0) {
110  // From the camera displacement cMc, compute the wMe and cMo matrices
111  cMo[i] = cMc.inverse() * cMo[i - 1];
112  wMe[i] = wMe[i - 1] * eMc * cMc * eMc.inverse();
113  }
114  }
115 
116  // if (1) {
117  if (1) {
118  for (unsigned int i = 0; i < N; i++) {
120  wMo = wMe[i] * eMc * cMo[i];
121  std::cout << std::endl << "wMo[" << i << "] " << std::endl;
122  std::cout << wMo << std::endl;
123  std::cout << "cMo[" << i << "] " << std::endl;
124  std::cout << cMo[i] << std::endl;
125  std::cout << "wMe[" << i << "] " << std::endl;
126  std::cout << wMe[i] << std::endl;
127  }
128  }
129 
130  // Reset the eMc matrix to eye
131  eMc.eye();
132 
133  // Compute the eMc hand to eye transformation from six poses
134  // - cMo[6]: camera to object poses as six homogeneous transformations
135  // - wMe[6]: world to hand (end-effector) poses as six homogeneous
136  // transformations
137  int ret = vpHandEyeCalibration::calibrate(cMo, wMe, eMc);
138 
139  if (ret == 0) {
140  std::cout << std::endl << "** Hand-eye calibration succeed" << std::endl;
141  std::cout << std::endl << "** Hand-eye (eMc) transformation estimated:" << std::endl;
142  std::cout << eMc << std::endl;
143  std::cout << "** Corresponding pose vector: " << vpPoseVector(eMc).t() << std::endl;
144  eMc.extract(erc);
145  std::cout << std::endl << "** Translation [m]: " << eMc[0][3] << " " << eMc[1][3] << " " << eMc[2][3] << std::endl;
146  std::cout << "** Rotation (theta-u representation) [rad]: " << erc.t() << std::endl;
147  std::cout << "** Rotation (theta-u representation) [deg]: " << vpMath::deg(erc[0]) << " " << vpMath::deg(erc[1]) << " " << 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 << "Check your input data and ensure they are covering the half sphere over the chessboard." << std::endl;
154  std::cout << std::endl << "See https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-calibration-extrinsic.html" << std::endl;
155  }
156 
157  return EXIT_SUCCESS;
158  } catch (const vpException &e) {
159  std::cout << "Catch an exception: " << e << std::endl;
160  return EXIT_FAILURE;
161  }
162 #else
163  std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl;
164  return EXIT_SUCCESS;
165 #endif
166 }
Implementation of an homogeneous matrix and operations on such kind of matrices.
static int calibrate(const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc)
vpRowVector t() const
error that can be emited by ViSP classes.
Definition: vpException.h:71
vpRotationMatrix getRotationMatrix() const
void extract(vpRotationMatrix &R) const
Implementation of a rotation vector as quaternion angle minimal representation.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
Definition: vpMath.h:110
static double deg(double rad)
Definition: vpMath.h:103
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:151
vpHomogeneousMatrix inverse() const
static vpHomogeneousMatrix direct(const vpColVector &v)
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
vpRowVector t() const