Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
visp-compute-eye-to-hand-calibration.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 * Compute eye-to-hand calibration from Apriltag poses and robot end-effector poses.
32 */
33
38#include <map>
39
40#include <visp3/core/vpConfig.h>
41#include <visp3/core/vpIoTools.h>
42#include <visp3/vision/vpHandEyeCalibration.h>
43
44void usage(const char *argv[], int error)
45{
46 std::cout << "Synopsis" << std::endl
47 << " " << argv[0]
48 << " [--data-path <path>]"
49 << " [--rPe <generic name>]"
50 << " [--cPo <generic name>]"
51 << " [--output-ePo <filename>]"
52 << " [--output-rPc <filename>]"
53 << " [--help, -h]" << std::endl
54 << std::endl;
55 std::cout << "Description" << std::endl
56 << " Compute eye-to-hand calibration." << std::endl
57 << std::endl
58 << " --data-path <path>" << std::endl
59 << " Path to the folder containing pose_rPe_%d.yaml and pose_cPo_%d.yaml data files." << std::endl
60 << " Default: \"./\"" << std::endl
61 << std::endl
62 << " --rPe <generic name>" << std::endl
63 << " Generic name of the yaml files containing the pose of the end-effector expressed in the robot" << std::endl
64 << " base frame and located in the data path folder." << std::endl
65 << " Default: pose_rPe_%d.yaml" << std::endl
66 << std::endl
67 << " --cPo <generic name>" << std::endl
68 << " Generic name of the yaml files" << std::endl
69 << " containing the pose of the calibration grid expressed in the camera frame and located in the" << std::endl
70 << " data path folder." << std::endl
71 << " Default: pose_cPo_%d.yaml" << std::endl
72 << std::endl
73 << " --output-ePo <filename>" << std::endl
74 << " File in yaml format containing the pose of the object" << std::endl
75 << " in the end-effector frame (eMo). Data are saved as a pose vector with first the 3 translations" << std::endl
76 << " along X,Y,Z in [m] and then the 3 rotations in axis-angle representation (thetaU) in [rad]." << std::endl
77 << " Default: ePo.yaml" << std::endl
78 << std::endl
79 << " --output-rPc <filename>" << std::endl
80 << " File in yaml format containing the pose of the camera" << std::endl
81 << " in the robot reference frame (rMc). Data are saved as a pose vector with first the 3 translations" << std::endl
82 << " along X,Y,Z in [m] and then the 3 rotations in axis-angle representation (thetaU) in [rad]." << std::endl
83 << " Default: rPc.yaml" << std::endl
84 << std::endl
85 << " --help, -h" << std::endl
86 << " Print this helper message." << std::endl
87 << std::endl;
88 if (error) {
89 std::cout << "Error" << std::endl
90 << " "
91 << "Unsupported parameter " << argv[error] << std::endl;
92 }
93}
94
95int main(int argc, const char *argv[])
96{
97#if defined(ENABLE_VISP_NAMESPACE)
98 using namespace VISP_NAMESPACE_NAME;
99#endif
100
101 std::string opt_data_path = "./";
102 std::string opt_rPe_files = "pose_rPe_%d.yaml";
103 std::string opt_cPo_files = "pose_cPo_%d.yaml";
104 std::string opt_ePo_file = "ePo.yaml";
105 std::string opt_rPc_file = "rPc.yaml";
106
107 for (int i = 1; i < argc; i++) {
108 if (std::string(argv[i]) == "--data-path" && i + 1 < argc) {
109 opt_data_path = std::string(argv[++i]);
110 }
111 else if (std::string(argv[i]) == "--rPe" && i + 1 < argc) {
112 opt_rPe_files = std::string(argv[++i]);
113 }
114 else if (std::string(argv[i]) == "--cPo" && i + 1 < argc) {
115 opt_cPo_files = std::string(argv[++i]);
116 }
117 else if (std::string(argv[i]) == "--output-ePo" && i + 1 < argc) {
118 opt_ePo_file = std::string(argv[++i]);
119 }
120 else if (std::string(argv[i]) == "--output-rPc" && i + 1 < argc) {
121 opt_rPc_file = std::string(argv[++i]);
122 }
123 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
124 usage(argv, 0);
125 return EXIT_SUCCESS;
126 }
127 else {
128 usage(argv, i);
129 return EXIT_FAILURE;
130 }
131 }
132
133 // Create output folder if necessary
134 std::string output_parent = vpIoTools::getParent(opt_ePo_file);
135 if (!vpIoTools::checkDirectory(output_parent)) {
136 std::cout << "Create output directory: " << output_parent << std::endl;
137 vpIoTools::makeDirectory(output_parent);
138 }
139
140 std::vector<vpHomogeneousMatrix> oMc;
141 std::vector<vpHomogeneousMatrix> rMe;
144
145 std::map<long, std::string> map_rPe_files;
146 std::map<long, std::string> map_cPo_files;
147 std::vector<std::string> files = vpIoTools::getDirFiles(opt_data_path);
148 for (unsigned int i = 0; i < files.size(); i++) {
149 long index_rPe = vpIoTools::getIndex(files[i], opt_rPe_files);
150 long index_cPo = vpIoTools::getIndex(files[i], opt_cPo_files);
151 if (index_rPe != -1) {
152 map_rPe_files[index_rPe] = files[i];
153 }
154 if (index_cPo != -1) {
155 map_cPo_files[index_cPo] = files[i];
156 }
157 }
158
159 if (map_rPe_files.size() == 0) {
160 std::cout << "No " << opt_rPe_files
161 << " files found. Use --data-path <path> or --rPe <generic name> to be able to read your data." << std::endl;
162 std::cout << "Use --help option to see full usage..." << std::endl;
163 return EXIT_FAILURE;
164 }
165 if (map_cPo_files.size() == 0) {
166 std::cout << "No " << opt_cPo_files
167 << " files found. Use --data-path <path> or --cPo <generic name> to be able to read your data." << std::endl;
168 std::cout << "Use --help option to see full usage..." << std::endl;
169 return EXIT_FAILURE;
170 }
171
172 for (std::map<long, std::string>::const_iterator it_rPe = map_rPe_files.begin(); it_rPe != map_rPe_files.end();
173 ++it_rPe) {
174 std::string file_rPe = vpIoTools::createFilePath(opt_data_path, it_rPe->second);
175 std::map<long, std::string>::const_iterator it_cPo = map_cPo_files.find(it_rPe->first);
176 if (it_cPo != map_cPo_files.end()) {
177 vpPoseVector rPe;
178 if (rPe.loadYAML(file_rPe, rPe) == false) {
179 std::cout << "Unable to read data from " << file_rPe << ". Skip data" << std::endl;
180 continue;
181 }
182
183 vpPoseVector cPo;
184 std::string file_cPo = vpIoTools::createFilePath(opt_data_path, it_cPo->second);
185 if (cPo.loadYAML(file_cPo, cPo) == false) {
186 std::cout << "Unable to read data from " << file_cPo << ". Skip data" << std::endl;
187 continue;
188 }
189 std::cout << "Use data from " << opt_data_path << "/" << file_rPe << " and from " << file_cPo << std::endl;
190 rMe.push_back(vpHomogeneousMatrix(rPe));
191 vpHomogeneousMatrix cMo, cMo_inv;
192 cMo.buildFrom(cPo);
193 cMo_inv = cMo.inverse();
194 vpPoseVector oPc(cMo_inv);
195 oMc.push_back(vpHomogeneousMatrix(oPc));
196 }
197 }
198
199 if (rMe.size() < 3) {
200 std::cout << "Not enough data pairs found." << std::endl;
201 return EXIT_FAILURE;
202 }
203
204 int ret = vpHandEyeCalibration::calibrate(oMc, rMe, eMo, rMc);
205
206 if (ret == 0) {
207 std::cout << std::endl << "Eye-to-hand calibration succeed" << std::endl;
208 std::cout << std::endl << "Estimated hand-object (eMo) transformation:" << std::endl;
209 std::cout << "-------------------------------------------" << std::endl;
210 //std::cout << eMo << std::endl;
211 vpMatrix(eMo).print(std::cout, 15, "eMo");
212 std::cout << "- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: " << vpPoseVector(eMo).t() << std::endl;
213
215 std::cout << std::endl << "- Translation [m]: " << eMo[0][3] << " " << eMo[1][3] << " " << eMo[2][3] << std::endl;
216 std::cout << "- Rotation (theta-u representation) [rad]: " << ero.t() << std::endl;
217 std::cout << "- Rotation (theta-u representation) [deg]: " << vpMath::deg(ero[0]) << " " << vpMath::deg(ero[1])
218 << " " << vpMath::deg(ero[2]) << std::endl;
219 vpQuaternionVector quaternion(eMo.getRotationMatrix());
220 std::cout << "- Rotation (quaternion representation) [rad]: " << quaternion.t() << std::endl;
222 std::cout << "- Rotation (r-x-y-z representation) [rad]: " << rxyz.t() << std::endl;
223 std::cout << "- Rotation (r-x-y-z representation) [deg]: " << vpMath::deg(rxyz).t() << std::endl;
224
225 std::cout << std::endl << "Estimated robot reference to camera frames (rMc) transformation:" << std::endl;
226 std::cout << "----------------------------------------------------------------" << std::endl;
227 //std::cout << rMc << std::endl;
228 vpMatrix(rMc).print(std::cout, 15, "rMc");
229 std::cout << "- Corresponding pose vector [tx ty tz tux tuy tuz] in [m] and [rad]: " << vpPoseVector(rMc).t() << std::endl;
230
232 std::cout << std::endl << "- Translation [m]: " << rMc[0][3] << " " << rMc[1][3] << " " << rMc[2][3] << std::endl;
233 std::cout << "- Rotation (theta-u representation) [rad]: " << wrc.t() << std::endl;
234 std::cout << "- Rotation (theta-u representation) [deg]: " << vpMath::deg(wrc[0]) << " " << vpMath::deg(wrc[1])
235 << " " << vpMath::deg(wrc[2]) << std::endl;
236 vpQuaternionVector quaternion2(rMc.getRotationMatrix());
237 std::cout << "- Rotation (quaternion representation) [rad]: " << quaternion2.t() << std::endl;
238 vpRxyzVector rxyz2(rMc.getRotationMatrix());
239 std::cout << "- Rotation (r-x-y-z representation) [rad]: " << rxyz2.t() << std::endl;
240 std::cout << "- Rotation (r-x-y-z representation) [deg]: " << vpMath::deg(rxyz).t() << std::endl;
241
242 {
243 // save eMo
244 std::string name_we = vpIoTools::createFilePath(vpIoTools::getParent(opt_ePo_file), vpIoTools::getNameWE(opt_ePo_file)) + ".txt";
245 std::cout << std::endl << "Save transformation matrix eMo as an homogeneous matrix in: " << name_we << std::endl;
246
247#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98)
248 std::ofstream file_eMo(name_we);
249#else
250 std::ofstream file_eMo(name_we.c_str());
251#endif
252
253 eMo.save(file_eMo);
254
255 vpPoseVector pose_vec(eMo);
256 std::string output_filename = vpIoTools::createFilePath(vpIoTools::getParent(opt_ePo_file), vpIoTools::getName(opt_ePo_file));
257 std::cout << "Save transformation matrix eMo as a vpPoseVector in : " << output_filename << std::endl;
258 pose_vec.saveYAML(output_filename, pose_vec, "Robot end-effector to object frames transformation (eMo)");
259 }
260
261 {
262 // save rMc
263 std::string name_we = vpIoTools::createFilePath(vpIoTools::getParent(opt_rPc_file), vpIoTools::getNameWE(opt_rPc_file)) + ".txt";
264 std::cout << std::endl << "Save transformation matrix rMc as an homogeneous matrix in: " << name_we << std::endl;
265
266#if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98)
267 std::ofstream file_rMc(name_we);
268#else
269 std::ofstream file_rMc(name_we.c_str());
270#endif
271
272 rMc.save(file_rMc);
273
274 vpPoseVector pose_vec(rMc);
275 std::string output_filename = vpIoTools::createFilePath(vpIoTools::getParent(opt_rPc_file), vpIoTools::getName(opt_rPc_file));
276 std::cout << "Save transformation matrix rMc as a vpPoseVector in : " << output_filename << std::endl;
277 pose_vec.saveYAML(output_filename, pose_vec, "Robot reference to camera frames transformation (rMc)");
278 }
279 }
280 else {
281 std::cout << std::endl << "** Eye-to-hand calibration failed" << std::endl;
282 std::cout << std::endl << "Check your input data and ensure they are covering the half sphere over the Apriltag." << std::endl;
283 std::cout << std::endl << "See https://visp-doc.inria.fr/doxygen/visp-daily/tutorial-calibration-extrinsic-eye-to-hand.html" << std::endl;
284 }
285
286 return EXIT_SUCCESS;
287}
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=nullptr)
Definition vpArray2D.h:874
vpArray2D< Type > t() const
Compute the transpose of the array.
Definition vpArray2D.h:1273
static int calibrate(const std::vector< vpHomogeneousMatrix > &cMo, const std::vector< vpHomogeneousMatrix > &rMe, vpHomogeneousMatrix &eMc, vpHomogeneousMatrix &rMo)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpRotationMatrix getRotationMatrix() const
void save(std::ofstream &f) const
static bool checkDirectory(const std::string &dirname)
static long getIndex(const std::string &filename, const std::string &format)
static std::string createFilePath(const std::string &parent, const std::string &child)
static std::vector< std::string > getDirFiles(const std::string &dirname)
static void makeDirectory(const std::string &dirname)
static std::string getNameWE(const std::string &pathname)
static std::string getParent(const std::string &pathname)
static std::string getName(const std::string &pathname)
static double deg(double rad)
Definition vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
int print(std::ostream &s, unsigned int length, const std::string &intro="") const
Definition vpMatrix.cpp:836
Implementation of a pose vector and operations on poses.
vpRowVector t() const
Implementation of a rotation vector as quaternion angle minimal representation.
Implementation of a rotation vector as Euler angle minimal representation.
Implementation of a rotation vector as axis-angle minimal representation.