Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
visp-compute-chessboard-poses.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 chessboard poses to prepare hand-eye calibration.
32 */
33
35#include <iostream>
36
37#include <visp3/core/vpConfig.h>
38
39#if defined(VISP_HAVE_PUGIXML) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_HIGHGUI) && \
40 (((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_CALIB)))
41
42#if defined(HAVE_OPENCV_CALIB3D)
43#include <opencv2/calib3d/calib3d.hpp>
44#elif defined(HAVE_OPENCV_CALIB)
45#include <opencv2/calib.hpp>
46#endif
47#include <opencv2/core/core.hpp>
48#include <opencv2/highgui/highgui.hpp>
49#include <opencv2/imgproc/imgproc.hpp>
50
51#include <visp3/core/vpIoTools.h>
52#include <visp3/core/vpPixelMeterConversion.h>
53#include <visp3/core/vpPoint.h>
54#include <visp3/core/vpXmlParserCamera.h>
55#if defined(VISP_HAVE_MODULE_GUI)
56#include <visp3/gui/vpDisplayFactory.h>
57#endif
58#include <visp3/io/vpVideoReader.h>
59#include <visp3/vision/vpPose.h>
60
61#if defined(ENABLE_VISP_NAMESPACE)
62using namespace VISP_NAMESPACE_NAME;
63#endif
64
65namespace
66{
67void calcChessboardCorners(int width, int height, double squareSize, std::vector<vpPoint> &corners)
68{
69 corners.resize(0);
70
71 for (int i = 0; i < height; i++) {
72 for (int j = 0; j < width; j++) {
73 vpPoint pt;
74 pt.set_oX(j * squareSize);
75 pt.set_oY(i * squareSize);
76 pt.set_oZ(0.0);
77 corners.push_back(pt);
78 }
79 }
80}
81
82void usage(const char **argv, int error)
83{
84 std::cout << "Synopsis" << std::endl
85 << " " << argv[0] << " [-w <width>] [-h <height>]"
86 << " [--square-size <size>]"
87 << " [--input <images filename>]"
88 << " [--intrinsic <xml file>]"
89 << " [--camera-name <name>]"
90 << " [--output <poses filename>]"
91 << " [--help, -h]" << std::endl
92 << std::endl;
93 std::cout << "Description" << std::endl
94 << " Compute the pose of a a chessboard in a sequence of images." << std::endl
95 << std::endl
96 << " -w <width>" << std::endl
97 << " Chessboard width." << std::endl
98 << " Default: 9" << std::endl
99 << std::endl
100 << " -h <height>" << std::endl
101 << " Chessboard height." << std::endl
102 << " Default: 6" << std::endl
103 << std::endl
104 << " --square-size <size>" << std::endl
105 << " Chessboard square size in [m]." << std::endl
106 << " Default: 0.03" << std::endl
107 << std::endl
108 << " --input <images filename>" << std::endl
109 << " Generic name of the images to process." << std::endl
110 << " Default: empty" << std::endl
111 << " Example: \"image-%d.jpg\"" << std::endl
112 << std::endl
113 << " --intrinsic <xml file>" << std::endl
114 << " XML file that contains camera intrinsic parameters. " << std::endl
115 << " Default: \"camera.xml\"" << std::endl
116 << std::endl
117 << " --camera-name <name>" << std::endl
118 << " Camera name in the XML file that contains camera intrinsic parameters." << std::endl
119 << " Default: \"Camera\"" << std::endl
120 << std::endl
121 << " --output <poses filename>" << std::endl
122 << " Generic name of the yaml files that contains the resulting tag poses." << std::endl
123 << " Default: \"pose_cPo_%d.yaml\"" << std::endl
124 << std::endl
125#if defined(VISP_HAVE_MODULE_GUI)
126 << " --no-interactive" << std::endl
127 << " To compute the tag poses without interactive validation by the user." << std::endl
128 << std::endl
129#endif
130 << " --help, -h" << std::endl
131 << " Print this helper message." << std::endl
132 << std::endl;
133
134 std::cout << "Example" << std::endl
135 << " "
136 << argv[0]
137 << " --input image-%d.jpg" << std::endl
138 << std::endl;
139
140 if (error) {
141 std::cout << "Error" << std::endl
142 << " "
143 << "Unsupported parameter " << argv[error] << std::endl;
144 }
145}
146} // namespace
147
148int main(int argc, const char **argv)
149{
150 int opt_chessboard_width = 9, opt_chessboard_height = 6;
151 double opt_chessboard_square_size = 0.03;
152 std::string opt_input_img_files = "";
153 std::string opt_intrinsic_file = "camera.xml";
154 std::string opt_camera_name = "Camera";
155 std::string opt_output_pose_files = "pose_cPo_%d.yaml";
156 bool opt_interactive = true;
157
158 for (int i = 1; i < argc; i++) {
159 if (std::string(argv[i]) == "-w" && i + 1 < argc) {
160 opt_chessboard_width = atoi(argv[++i]);
161 }
162 else if (std::string(argv[i]) == "-h" && i + 1 < argc) {
163 opt_chessboard_height = atoi(argv[++i]);
164 }
165 else if (std::string(argv[i]) == "--square-size" && i + 1 < argc) {
166 opt_chessboard_square_size = atof(argv[++i]);
167 }
168 else if (std::string(argv[i]) == "--input" && i + 1 < argc) {
169 opt_input_img_files = std::string(argv[++i]);
170 }
171 else if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) {
172 opt_intrinsic_file = std::string(argv[++i]);
173 }
174 else if (std::string(argv[i]) == "--output" && i + 1 < argc) {
175 opt_output_pose_files = std::string(argv[++i]);
176 }
177 else if (std::string(argv[i]) == "--camera-name" && i + 1 < argc) {
178 opt_camera_name = std::string(argv[++i]);
179 }
180#if defined(VISP_HAVE_MODULE_GUI)
181 else if (std::string(argv[i]) == "--no-interactive") {
182 opt_interactive = false;
183 }
184#endif
185 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
186 usage(argv, 0);
187 return EXIT_SUCCESS;
188 }
189 else {
190 usage(argv, i);
191 return EXIT_FAILURE;
192 }
193 }
194
195 if (!vpIoTools::checkFilename(opt_intrinsic_file)) {
196 std::cout << "Camera parameters file " << opt_intrinsic_file << " doesn't exist." << std::endl;
197 std::cout << "Use --help option to see how to set its location..." << std::endl;
198 return EXIT_FAILURE;
199 }
200
201 if (opt_input_img_files.empty()) {
202 std::cout << "Input images location empty." << std::endl;
203 std::cout << "Use --help option to see how to set input image location..." << std::endl;
204 return EXIT_FAILURE;
205 }
206
207 try {
208 vpVideoReader reader;
209 reader.setFileName(opt_input_img_files);
210
212 reader.open(I);
213
214 std::cout << "Parameters:" << std::endl;
215 std::cout << " Chessboard" << std::endl;
216 std::cout << " Width : " << opt_chessboard_width << std::endl;
217 std::cout << " Height : " << opt_chessboard_height << std::endl;
218 std::cout << " Square size [m] : " << opt_chessboard_square_size << std::endl;
219 std::cout << " Input images location : " << opt_input_img_files << std::endl;
220 std::cout << " First frame : " << reader.getFirstFrameIndex() << std::endl;
221 std::cout << " Last frame : " << reader.getLastFrameIndex() << std::endl;
222 std::cout << " Camera intrinsics " << std::endl;
223 std::cout << " Param file name [.xml]: " << opt_intrinsic_file << std::endl;
224 std::cout << " Camera name : " << opt_camera_name << std::endl;
225 std::cout << " Output camera poses : " << opt_output_pose_files << std::endl;
226 std::cout << " Interactive mode : " << (opt_interactive ? "yes" : "no") << std::endl << std::endl;
227
228#if defined(VISP_HAVE_MODULE_GUI)
229#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
230 std::shared_ptr<vpDisplay> display;
231#else
232 vpDisplay *display = nullptr;
233#endif
234 if (opt_interactive) {
235#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
237#else
239#endif
240 }
241#endif
242
243 // Create output folder if necessary
244 std::string output_parent = vpIoTools::getParent(opt_output_pose_files);
245 if (!vpIoTools::checkDirectory(output_parent)) {
246 std::cout << "Create output directory: " << output_parent << std::endl;
247 vpIoTools::makeDirectory(output_parent);
248 }
249
250 std::vector<vpPoint> corners_pts;
251 calcChessboardCorners(opt_chessboard_width, opt_chessboard_height, opt_chessboard_square_size, corners_pts);
252
255 if (!opt_intrinsic_file.empty() && !opt_camera_name.empty()) {
256 if (parser.parse(cam, opt_intrinsic_file, opt_camera_name, vpCameraParameters::perspectiveProjWithDistortion) !=
258 std::cout << "Unable to parse parameters with distortion for camera \"" << opt_camera_name << "\" from "
259 << opt_intrinsic_file << " file" << std::endl;
260 std::cout << "Attempt to find parameters without distortion" << std::endl;
261
262 if (parser.parse(cam, opt_intrinsic_file, opt_camera_name,
264 std::cout << "Unable to parse parameters without distortion for camera \"" << opt_camera_name << "\" from "
265 << opt_intrinsic_file << " file" << std::endl;
266 return EXIT_FAILURE;
267 }
268 }
269 }
270 std::cout << "Camera parameters used to compute the pose:\n" << cam << std::endl;
271
272 bool quit = false;
273 do {
274 reader.acquire(I);
275 std::cout << "Process image: " << reader.getFrameName() << std::endl;
276
277 cv::Mat matImg;
278 vpImageConvert::convert(I, matImg);
279
280#if defined(VISP_HAVE_MODULE_GUI)
282#endif
283
284 cv::Size chessboardSize(opt_chessboard_width, opt_chessboard_height);
285 std::vector<cv::Point2f> corners2D;
286 bool found = cv::findChessboardCorners(matImg, chessboardSize, corners2D,
287#if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
288 cv::CALIB_CB_ADAPTIVE_THRESH | cv::CALIB_CB_FAST_CHECK |
289 cv::CALIB_CB_NORMALIZE_IMAGE);
290#else
291 CV_CALIB_CB_ADAPTIVE_THRESH | CV_CALIB_CB_FAST_CHECK |
292 CV_CALIB_CB_NORMALIZE_IMAGE);
293#endif
294
296 if (found) {
297 cv::Mat matImg_gray;
298 cv::cvtColor(matImg, matImg_gray, cv::COLOR_BGR2GRAY);
299 cv::cornerSubPix(matImg_gray, corners2D, cv::Size(11, 11), cv::Size(-1, -1),
300#if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
301 cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::COUNT, 30, 0.1));
302#else
303 cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 30, 0.1));
304#endif
305
306 for (size_t i = 0; i < corners_pts.size(); i++) {
307 vpImagePoint imPt(corners2D[i].y, corners2D[i].x);
308 double x = 0.0, y = 0.0;
310 corners_pts[i].set_x(x);
311 corners_pts[i].set_y(y);
312 }
313
314 vpPose pose;
315 pose.addPoints(corners_pts);
317 std::cerr << "Problem when computing final pose using VVS" << std::endl;
318 return EXIT_FAILURE;
319 }
320
321 cv::drawChessboardCorners(matImg, chessboardSize, corners2D, found);
322 vpImageConvert::convert(matImg, I);
323 }
324
325 if (found) {
326 vpPoseVector pose_vec(cMo);
327 std::string filename = vpIoTools::formatString(opt_output_pose_files, reader.getFrameIndex());
328 pose_vec.saveYAML(filename, pose_vec);
329 }
330
331#if defined(VISP_HAVE_MODULE_GUI)
332 if (opt_interactive) {
334 vpDisplay::displayText(I, 20, 20, "Left click for the next image, right click to quit.", vpColor::red);
335 if (found) {
336 vpDisplay::displayFrame(I, cMo, cam, 0.05, vpColor::none, 3);
337 }
339
341 if (vpDisplay::getClick(I, button, true)) {
342 if (button == vpMouseButton::button3) {
343 quit = true;
344 }
345 }
346 }
347#endif
348 } while (!quit && !reader.end());
349
350#if defined(VISP_HAVE_MODULE_GUI)
351 if (opt_interactive) {
352#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
353 if (display) {
354 delete display;
355 }
356#endif
357 }
358#endif
359 }
360 catch (const vpException &e) {
361 std::cout << "Catch an exception: " << e.getMessage() << std::endl;
362 }
363
364 return EXIT_SUCCESS;
365}
366#else
367int main()
368{
369#if !defined(HAVE_OPENCV_IMGPROC)
370 std::cerr << "OpenCV imgproc module is requested to compute the pose of the chessboard." << std::endl;
371#endif
372#if !defined(HAVE_OPENCV_HIGHGUI)
373 std::cerr << "OpenCV highgui module is requested to compute the pose of the chessboard." << std::endl;
374#endif
375#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION < 0x050000) && !defined(HAVE_OPENCV_CALIB3D)
376 std::cerr << "OpenCV calib3d module is requested to compute the pose of the chessboard." << std::endl;
377#endif
378#if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x050000) && !defined(HAVE_OPENCV_3D)
379 std::cerr << "OpenCV 3d module is requested to compute the pose of the chessboard." << std::endl;
380#endif
381#if !defined(VISP_HAVE_PUGIXML)
382 std::cout << "pugixml built-in 3rdparty is requested to compute the pose of the chessboard." << std::endl;
383#endif
384 return EXIT_SUCCESS;
385}
386#endif
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
static const vpColor red
Definition vpColor.h:198
static const vpColor none
Definition vpColor.h:210
Class that defines generic functionalities for display.
Definition vpDisplay.h:171
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void setTitle(const vpImage< unsigned char > &I, const std::string &windowtitle)
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Definition vpException.h:60
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition of the vpImage class member functions.
Definition vpImage.h:131
static bool checkFilename(const std::string &filename)
static bool checkDirectory(const std::string &dirname)
static std::string formatString(const std::string &name, unsigned int val)
static void makeDirectory(const std::string &dirname)
static std::string getParent(const std::string &pathname)
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition vpPoint.h:79
void set_oY(double oY)
Set the point oY coordinate in the object frame.
Definition vpPoint.cpp:464
void set_oZ(double oZ)
Set the point oZ coordinate in the object frame.
Definition vpPoint.cpp:466
void set_oX(double oX)
Set the point oX coordinate in the object frame.
Definition vpPoint.cpp:462
Implementation of a pose vector and operations on poses.
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition vpPose.h:82
@ DEMENTHON_LAGRANGE_VIRTUAL_VS
Definition vpPose.h:103
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, FuncCheckValidityPose func=nullptr)
Definition vpPose.cpp:385
void addPoints(const std::vector< vpPoint > &lP)
Definition vpPose.cpp:103
Class that enables to manipulate easily a video file or a sequence of images. As it inherits from the...
long getLastFrameIndex()
void open(vpImage< vpRGBa > &I) VP_OVERRIDE
void setFileName(const std::string &filename)
long getFirstFrameIndex()
std::string getFrameName() const
long getFrameIndex() const
void acquire(vpImage< vpRGBa > &I) VP_OVERRIDE
XML parser to load and save intrinsic camera parameters.
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.