Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
catchArUco.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 * Test ArUco detection.
32 */
38
39#include <visp3/core/vpConfig.h>
40
41#if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_APRILTAG)
42
43#include <catch_amalgamated.hpp>
44
45#include <iostream>
46#include <visp3/core/vpImageTools.h>
47#include <visp3/core/vpImageConvert.h>
48#include <visp3/detection/vpDetectorAprilTag.h>
49
50#if (VISP_HAVE_OPENCV_VERSION >= 0x040700)
51#include <opencv2/objdetect/aruco_detector.hpp>
52#include <opencv2/calib3d.hpp>
53using namespace cv;
54#endif
55
56#ifdef ENABLE_VISP_NAMESPACE
57using namespace VISP_NAMESPACE_NAME;
58#endif
59
60
61static bool g_debug_print = false;
62
63bool opt_no_display = false; // If true, disable display or tests requiring display
64
65TEST_CASE("ArUco detection test", "[aruco_detection_test]")
66{
67 std::map<vpDetectorAprilTag::vpAprilTagFamily, int> apriltagMap = {
72
77
82
87
89 };
90
91 const int nb_tests = 50;
92 SECTION("Constructor")
93 {
94 for (const auto &kv : apriltagMap) {
95 vpDetectorAprilTag detector(kv.first);
96
97 for (int id = 0; id < kv.second; id += kv.second/nb_tests) {
99 detector.getTagImage(tag_img, id);
100
101 vpImage<unsigned char> tag_img_big(tag_img.getHeight()*20, tag_img.getWidth()*20);
103
104 bool detect = detector.detect(tag_img_big);
105 CHECK(detect == true);
106 if (detect) {
107 bool found_id = false;
108 // Parse the message
109 for (size_t i = 0; i < detector.getNbObjects(); i++) {
110 std::string message = detector.getMessage(i);
111 std::size_t tag_id_pos = message.find("id: ");
112
113 if (tag_id_pos != std::string::npos) {
114 int tag_id = atoi(message.substr(tag_id_pos + 4).c_str());
115 if (g_debug_print) {
116 WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
117 }
118 if (tag_id == id) {
119 found_id = true;
120 }
121 }
122 }
123 CHECK(found_id == true);
124
125 found_id = false;
126 // Use directly the getter
127 std::vector<int> tagsId = detector.getTagsId();
128 for (auto tag_id : tagsId) {
129 if (g_debug_print) {
130 WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
131 }
132 if (tag_id == id) {
133 found_id = true;
134 break;
135 }
136 }
137 CHECK(found_id == true);
138 }
139 }
140 }
141 }
142
143 SECTION("Copy constructor")
144 {
145 for (const auto &kv : apriltagMap) {
146 vpDetectorAprilTag detector(kv.first);
147
148 for (int id = 0; id < kv.second; id += kv.second/nb_tests) {
150 detector.getTagImage(tag_img, id);
151
152 vpImage<unsigned char> tag_img_big(tag_img.getHeight()*20, tag_img.getWidth()*20);
154
155 bool detect = detector.detect(tag_img_big);
156 CHECK(detect == true);
157 if (detect) {
158 std::vector<int> tagsId = detector.getTagsId();
159 std::vector<float> tagsDecisionMargin = detector.getTagsDecisionMargin();
160 std::vector<int> tagsHammingDistance = detector.getTagsHammingDistance();
161 CHECK(tagsId.size() == tagsDecisionMargin.size());
162 CHECK(tagsId.size() == tagsHammingDistance.size());
163 CHECK(tagsId.size() == detector.getNbObjects());
164
165 // Use directly the getter
166 bool found_id = false;
167 for (auto tag_id : tagsId) {
168 if (g_debug_print) {
169 WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
170 }
171 if (tag_id == id) {
172 found_id = true;
173 break;
174 }
175 }
176 CHECK(found_id == true);
177 }
178 }
179 }
180 }
181
182 SECTION("Getter/Setter")
183 {
184 for (const auto &kv : apriltagMap) {
185 vpDetectorAprilTag detector(kv.first);
186 int hamming_dist_ref = 0;
187 float decision_margin = 50.0f;
188 detector.setAprilTagHammingDistanceThreshold(hamming_dist_ref);
189 detector.setAprilTagDecisionMarginThreshold(decision_margin);
190 CHECK(detector.getAprilTagHammingDistanceThreshold() == hamming_dist_ref);
191 CHECK(detector.getAprilTagDecisionMarginThreshold() == decision_margin);
192
193 for (int id = 0; id < kv.second; id += kv.second/nb_tests) {
195 detector.getTagImage(tag_img, id);
196
197 vpImage<unsigned char> tag_img_big(tag_img.getHeight()*20, tag_img.getWidth()*20);
199
200 bool detect = detector.detect(tag_img_big);
201 CHECK(detect == true);
202 if (detect) {
203 std::vector<int> tagsId = detector.getTagsId();
204 std::vector<float> tagsDecisionMargin = detector.getTagsDecisionMargin();
205 std::vector<int> tagsHammingDistance = detector.getTagsHammingDistance();
206 CHECK(tagsId.size() == tagsDecisionMargin.size());
207 CHECK(tagsId.size() == tagsHammingDistance.size());
208 CHECK(tagsId.size() == detector.getNbObjects());
209
210 // Use directly the getter
211 bool found_id = false;
212 for (auto tag_id : tagsId) {
213 if (g_debug_print) {
214 WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << id);
215 }
216 if (tag_id == id) {
217 found_id = true;
218 break;
219 }
220 }
221 CHECK(found_id == true);
222 }
223 }
224 }
225 }
226}
227
228#if (VISP_HAVE_OPENCV_VERSION >= 0x040800)
229TEST_CASE("ArUco pose computation test", "[aruco_detection_test]")
230{
231 std::map<vpDetectorAprilTag::vpAprilTagFamily, aruco::PredefinedDictionaryType> apriltagMap = {
232 {vpDetectorAprilTag::TAG_ARUCO_4x4_50, aruco::PredefinedDictionaryType::DICT_4X4_50},
233 {vpDetectorAprilTag::TAG_ARUCO_5x5_50, aruco::PredefinedDictionaryType::DICT_5X5_50},
234 {vpDetectorAprilTag::TAG_ARUCO_6x6_50, aruco::PredefinedDictionaryType::DICT_6X6_50},
235 {vpDetectorAprilTag::TAG_ARUCO_7x7_50, aruco::PredefinedDictionaryType::DICT_7X7_50},
236 {vpDetectorAprilTag::TAG_ARUCO_MIP_36h12, aruco::PredefinedDictionaryType::DICT_ARUCO_MIP_36h12}
237 };
238
239 const float markerLength = 0.05f;
240
241 // ViSP
242 vpCameraParameters cam(600, 600, 100/2, 100/2);
243 std::vector<vpHomogeneousMatrix> cMo_vec;
244
245 // OpenCV
246 aruco::DetectorParameters detectorParams;
247 Matx33d camMatrix = Matx33d::eye();
248 camMatrix(0, 0) = cam.get_px(); camMatrix(0, 2) = cam.get_u0();
249 camMatrix(1, 1) = cam.get_py(); camMatrix(1, 2) = cam.get_v0();
250 Matx41d distCoeffs = Matx41d::zeros();
251 Mat image;
252
253 Mat objPoints(4, 1, CV_32FC3);
254 objPoints.ptr<Vec3f>(0)[0] = Vec3f(-markerLength/2.f, markerLength/2.f, 0);
255 objPoints.ptr<Vec3f>(0)[1] = Vec3f(markerLength/2.f, markerLength/2.f, 0);
256 objPoints.ptr<Vec3f>(0)[2] = Vec3f(markerLength/2.f, -markerLength/2.f, 0);
257 objPoints.ptr<Vec3f>(0)[3] = Vec3f(-markerLength/2.f, -markerLength/2.f, 0);
258
259 for (const auto &kv : apriltagMap) {
260 // ViSP
261 vpDetectorAprilTag detector(kv.first);
262
263 // OpenCV
264 aruco::ArucoDetector cv_detector(aruco::getPredefinedDictionary(kv.second), detectorParams);
265 std::vector<int> ids;
266 std::vector<std::vector<Point2f> > corners, rejected;
267
268 const int tag_id_ref = 3;
270 detector.getTagImage(tag_img, tag_id_ref);
271
272 vpImage<unsigned char> tag_img_big(tag_img.getHeight()*20, tag_img.getWidth()*20);
274 vpImageConvert::convert(tag_img_big, image);
275
276 bool detect = detector.detect(tag_img_big, markerLength, cam, cMo_vec);
277 CHECK(detect == true);
278 if (detect) {
279 std::vector<int> tagsId = detector.getTagsId();
280 std::vector<float> tagsDecisionMargin = detector.getTagsDecisionMargin();
281 std::vector<int> tagsHammingDistance = detector.getTagsHammingDistance();
282 CHECK(tagsId.size() == tagsDecisionMargin.size());
283 CHECK(tagsId.size() == tagsHammingDistance.size());
284 CHECK(tagsId.size() == detector.getNbObjects());
285 CHECK(tagsId.size() == cMo_vec.size());
286
288 // Use directly the getter
289 bool found_id = false;
290 for (size_t idx = 0; idx < tagsId.size(); idx++) {
291 int tag_id = tagsId[idx];
292 if (g_debug_print) {
293 WARN("tag_dict=" << kv.first << " ; tag_id=" << tag_id << " ; tag_ref=" << tag_id_ref);
294 }
295 if (tag_id == tag_id_ref) {
296 cMo = cMo_vec[idx];
297 found_id = true;
298 break;
299 }
300 }
301
302 CHECK(found_id == true);
303 if (found_id) {
304 // OpenCV detect markers and estimate pose
305 cv_detector.detectMarkers(image, corners, ids, rejected);
306 CHECK(!ids.empty());
307
308 size_t idx_tag_id_ref = 0;
309 bool found_tag_id_ref = false;
310 for (size_t i = 0; i < ids.size(); i++) {
311 if (ids[i] == tag_id_ref) {
312 found_tag_id_ref = true;
313 idx_tag_id_ref = i;
314 }
315 }
316
317 CHECK(found_tag_id_ref);
318 if (found_tag_id_ref) {
319 Matx31d rvec, tvec;
320 solvePnP(objPoints, corners.at(idx_tag_id_ref), camMatrix, distCoeffs, rvec, tvec);
321 vpThetaUVector cro = cMo.getThetaUVector();
322 if (g_debug_print) {
323 WARN("rvec: " << rvec(0) << " " << rvec(1) << " " << rvec(2));
324 WARN("tvec: " << tvec(0) << " " << tvec(1) << " " << tvec(2));
325
326 WARN("cro: " << cro[0] << " " << cro[1] << " " << cro[2]);
327 WARN("cto: " << cMo[0][3] << " " << cMo[1][3] << " " << cMo[2][3]);
328 }
329
330 CHECK_THAT(tvec(0), Catch::Matchers::WithinAbs(cMo[0][3], 1e-2));
331 CHECK_THAT(tvec(1), Catch::Matchers::WithinAbs(cMo[1][3], 1e-2));
332 CHECK_THAT(tvec(2), Catch::Matchers::WithinAbs(cMo[2][3], 1e-2));
333
334 double rvec_magn = std::sqrt(rvec(0)*rvec(0) + rvec(1)*rvec(1) + rvec(2)*rvec(2));
335 double cro_magn = std::sqrt(cro[0]*cro[0] + cro[1]*cro[1] + cro[2]*cro[2]);
336 CHECK_THAT(rvec_magn, Catch::Matchers::WithinAbs(cro_magn, 1e-2));
337 }
338 }
339 }
340 }
341}
342#endif
343
344int main(int argc, const char *argv[])
345{
346 Catch::Session session;
347
348 using namespace Catch::Clara;
349 auto cli = session.cli()
350 | Catch::Clara::Opt(g_debug_print)["--debug-print"]("Force the printing of some debug information.")
351 | Catch::Clara::Opt(opt_no_display)["--no-display"]("Disable display");
352
353 session.cli(cli);
354 int returnCode = session.applyCommandLine(argc, argv);
355 if (returnCode != 0) { // Indicates a command line error
356 return returnCode;
357 }
358
359 int numFailed = session.run();
360 return numFailed;
361}
362
363#else
364int main() { return EXIT_SUCCESS; }
365#endif
Generic class defining intrinsic camera parameters.
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static void resize(const vpImage< Type > &I, vpImage< Type > &Ires, unsigned int width, unsigned int height, const vpImageInterpolationType &method=INTERPOLATION_NEAREST, unsigned int nThreads=0)
Definition of the vpImage class member functions.
Definition vpImage.h:131
unsigned int getWidth() const
Definition vpImage.h:242
unsigned int getHeight() const
Definition vpImage.h:181
Implementation of a rotation vector as axis-angle minimal representation.