Visual Servoing Platform  version 3.3.0 under development (2020-02-17)
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  try {
60  // We want to calibrate the hand-eye extrinsic camera parameters from 6
61  // couple of poses: cMo and wMe
62  const unsigned int N = 6;
63  // Input: six couple of poses used as input in the calibration proces
64  std::vector<vpHomogeneousMatrix> cMo(N); // eye (camera) to object
65  // transformation. The object
66  // frame is attached to the
67  // calibrartion grid
68  std::vector<vpHomogeneousMatrix> wMe(N); // world to hand (end-effector) transformation
69  // Output: Result of the calibration
70  vpHomogeneousMatrix eMc; // hand (end-effector) to eye (camera) transformation
71 
72  // Initialize an eMc transformation used to produce the simulated input
73  // transformations cMo and wMe
74  vpTranslationVector etc(0.1, 0.2, 0.3);
75  vpThetaUVector erc;
76  erc[0] = vpMath::rad(10); // 10 deg
77  erc[1] = vpMath::rad(-10); // -10 deg
78  erc[2] = vpMath::rad(25); // 25 deg
79 
80  eMc.buildFrom(etc, erc);
81  std::cout << "Simulated hand-eye transformation: eMc " << std::endl;
82  std::cout << eMc << std::endl;
83  std::cout << "Theta U rotation: " << vpMath::deg(erc[0]) << " " << vpMath::deg(erc[1]) << " " << vpMath::deg(erc[2])
84  << std::endl;
85 
86  vpColVector v_c(6); // camera velocity used to produce 6 simulated poses
87  for (unsigned int i = 0; i < N; i++) {
88  v_c = 0;
89  if (i == 0) {
90  // Initialize first poses
91  cMo[0].buildFrom(0, 0, 0.5, 0, 0, 0); // z=0.5 m
92  wMe[0].buildFrom(0, 0, 0, 0, 0, 0); // Id
93  } else if (i == 1)
94  v_c[3] = M_PI/8 ;
95  else if (i == 2)
96  v_c[4] = M_PI/8 ;
97  else if (i == 3)
98  v_c[5] = M_PI/10 ;
99  else if (i == 4)
100  v_c[0] = 0.5;
101  else if (i == 5)
102  v_c[1] = 0.8;
103 
104  vpHomogeneousMatrix cMc; // camera displacement
105  cMc = vpExponentialMap::direct(v_c); // Compute the camera displacement
106  // due to the velocity applied to
107  // the camera
108  if (i > 0) {
109  // From the camera displacement cMc, compute the wMe and cMo matrices
110  cMo[i] = cMc.inverse() * cMo[i - 1];
111  wMe[i] = wMe[i - 1] * eMc * cMc * eMc.inverse();
112  }
113  }
114 
115  // if (1) {
116  if (1) {
117  for (unsigned int i = 0; i < N; i++) {
119  wMo = wMe[i] * eMc * cMo[i];
120  std::cout << std::endl << "wMo[" << i << "] " << std::endl;
121  std::cout << wMo << std::endl;
122  std::cout << "cMo[" << i << "] " << std::endl;
123  std::cout << cMo[i] << std::endl;
124  std::cout << "wMe[" << i << "] " << std::endl;
125  std::cout << wMe[i] << std::endl;
126  }
127  }
128 
129  // Reset the eMc matrix to eye
130  eMc.eye();
131 
132  // Compute the eMc hand to eye transformation from six poses
133  // - cMo[6]: camera to object poses as six homogeneous transformations
134  // - wMe[6]: world to hand (end-effector) poses as six homogeneous
135  // transformations
136  vpHandEyeCalibration::calibrate(cMo, wMe, eMc);
137 
138  std::cout << std::endl << "Output: hand-eye calibration result: eMc estimated " << std::endl;
139  std::cout << eMc << std::endl;
140  eMc.extract(erc);
141  std::cout << "Theta U rotation: " << vpMath::deg(erc[0]) << " " << vpMath::deg(erc[1]) << " " << vpMath::deg(erc[2])
142  << std::endl;
143  return EXIT_SUCCESS;
144  } catch (const vpException &e) {
145  std::cout << "Catch an exception: " << e << std::endl;
146  return EXIT_FAILURE;
147  }
148 }
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)
error that can be emited by ViSP classes.
Definition: vpException.h:71
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double rad(double deg)
Definition: vpMath.h:108
static double deg(double rad)
Definition: vpMath.h:101
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
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.