Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
catchAprilTag.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 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 AprilTag detection.
32  */
39 #include <visp3/core/vpConfig.h>
40 
41 #if defined(VISP_HAVE_CATCH2) && defined(VISP_HAVE_APRILTAG) && (VISP_HAVE_DATASET_VERSION >= 0x030300)
42 
43 #include <catch_amalgamated.hpp>
44 
45 #include <iostream>
46 #include <visp3/core/vpDisplay.h>
47 #include <visp3/core/vpIoTools.h>
48 #include <visp3/core/vpPixelMeterConversion.h>
49 #include <visp3/core/vpPoint.h>
50 #include <visp3/detection/vpDetectorAprilTag.h>
51 #include <visp3/io/vpImageIo.h>
52 #include <visp3/vision/vpPose.h>
53 
54 #ifdef ENABLE_VISP_NAMESPACE
55 using namespace VISP_NAMESPACE_NAME;
56 #endif
57 namespace
58 {
59 struct TagGroundTruth
60 {
61  std::string m_message;
62  std::vector<vpImagePoint> m_corners;
63 
64  TagGroundTruth(const std::string &msg, const std::vector<vpImagePoint> &c) : m_message(msg), m_corners(c) { }
65 
66  bool operator==(const TagGroundTruth &b) const
67  {
68  if (m_message != b.m_message || m_corners.size() != b.m_corners.size()) {
69  return false;
70  }
71 
72  for (size_t i = 0; i < m_corners.size(); i++) {
73  // Allow 0.5 pixel of difference
74  if (!vpMath::equal(m_corners[i].get_u(), b.m_corners[i].get_u(), 0.5) ||
75  !vpMath::equal(m_corners[i].get_v(), b.m_corners[i].get_v(), 0.5)) {
76  return false;
77  }
78  }
79 
80  return true;
81  }
82 
83  bool operator!=(const TagGroundTruth &b) const { return !(*this == b); }
84 
85  double rmse(const std::vector<vpImagePoint> &c)
86  {
87  double error = 0;
88 
89  if (m_corners.size() == c.size()) {
90  for (size_t i = 0; i < m_corners.size(); i++) {
91  const vpImagePoint &a = m_corners[i];
92  const vpImagePoint &b = c[i];
93  error += (a.get_i() - b.get_i()) * (a.get_i() - b.get_i()) + (a.get_j() - b.get_j()) * (a.get_j() - b.get_j());
94  }
95  }
96  else {
97  return -1;
98  }
99 
100  return sqrt(error / (2 * m_corners.size()));
101  }
102 };
103 
104 #if defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_EIGEN3)
105 std::ostream &operator<<(std::ostream &os, TagGroundTruth &t)
106 {
107  os << t.m_message << std::endl;
108  for (size_t i = 0; i < t.m_corners.size(); i++) {
109  os << t.m_corners[i] << std::endl;
110  }
111 
112  return os;
113 }
114 #endif
115 
116 struct FailedTestCase
117 {
120  int m_tagId;
121 
122  FailedTestCase(const vpDetectorAprilTag::vpAprilTagFamily &family,
123  const vpDetectorAprilTag::vpPoseEstimationMethod &method, int tagId)
124  : m_family(family), m_method(method), m_tagId(tagId)
125  { }
126 
127  bool operator==(const FailedTestCase &b) const
128  {
129  return m_family == b.m_family && m_method == b.m_method && m_tagId == b.m_tagId;
130  }
131 
132  bool operator!=(const FailedTestCase &b) const { return !(*this == b); }
133 };
134 } // namespace
135 
136 TEST_CASE("Apriltag pose estimation test", "[apriltag_pose_estimation_test]")
137 {
138  std::map<vpDetectorAprilTag::vpAprilTagFamily, std::string> apriltagMap = {
139  {vpDetectorAprilTag::TAG_16h5, "tag16_05"},
140  {vpDetectorAprilTag::TAG_25h9, "tag25_09"},
141  {vpDetectorAprilTag::TAG_36h11, "tag36_11"},
143 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
144  ,
149 #endif
150  };
151 
152  std::map<vpDetectorAprilTag::vpAprilTagFamily, double> tagSizeScales = {
153  {vpDetectorAprilTag::TAG_16h5, 6.0 / 8},
154  {vpDetectorAprilTag::TAG_25h9, 7.0 / 9},
155  {vpDetectorAprilTag::TAG_36h11, 8.0 / 10},
157 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
158  ,
163 #endif
164  };
165 
166  std::vector<vpDetectorAprilTag::vpPoseEstimationMethod> poseMethods = {
169 #if defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_EIGEN3)
174 #endif
175  };
176  std::map<vpDetectorAprilTag::vpPoseEstimationMethod, std::string> methodNames = {
177  {vpDetectorAprilTag::HOMOGRAPHY, "HOMOGRAPHY"},
178  {vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS, "HOMOGRAPHY_VIRTUAL_VS"},
179  {vpDetectorAprilTag::HOMOGRAPHY_ORTHOGONAL_ITERATION, "HOMOGRAPHY_ORTHOGONAL_ITERATION"},
180 #if defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_EIGEN3)
181  {vpDetectorAprilTag::DEMENTHON_VIRTUAL_VS, "DEMENTHON_VIRTUAL_VS"},
182  {vpDetectorAprilTag::LAGRANGE_VIRTUAL_VS, "LAGRANGE_VIRTUAL_VS"},
183  {vpDetectorAprilTag::BEST_RESIDUAL_VIRTUAL_VS, "BEST_RESIDUAL_VIRTUAL_VS"}
184 #endif
185  };
186 
187  const size_t nbTags = 5;
188  const double tagSize_ = 0.25;
189  std::map<int, double> tagsSize = {
190  {0, tagSize_}, {1, tagSize_}, {2, tagSize_}, {3, tagSize_ / 2}, {4, tagSize_ / 2},
191  };
192 
193  std::map<int, double> errorTranslationThresh = {
194  {0, 0.025}, {1, 0.09}, {2, 0.05}, {3, 0.13}, {4, 0.09},
195  };
196  std::map<int, double> errorRotationThresh = {
197  {0, 0.04}, {1, 0.075}, {2, 0.07}, {3, 0.18}, {4, 0.13},
198  };
199  std::vector<FailedTestCase> ignoreTests = {
203 
204  vpCameraParameters cam;
205  cam.initPersProjWithoutDistortion(700.0, 700.0, 320.0, 240.0);
206 
207  std::map<int, vpHomogeneousMatrix> groundTruthPoses;
208  for (size_t i = 0; i < nbTags; i++) {
209  std::string filename =
210  vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), std::string("AprilTag/benchmark/640x480/cMo_") +
211  std::to_string(i) + std::string(".txt"));
212  std::ifstream file(filename);
213  groundTruthPoses[static_cast<int>(i)].load(file);
214  }
215 
216  for (const auto &kv : apriltagMap) {
217  auto family = kv.first;
218  std::cout << "\nApriltag family: " << family << std::endl;
219  std::string filename =
221  std::string("AprilTag/benchmark/640x480/") + kv.second + std::string("_640x480.png"));
222  const double tagSize = tagSize_ * tagSizeScales[family];
223  REQUIRE(vpIoTools::checkFilename(filename));
224 
226  vpImageIo::read(I, filename);
227  REQUIRE(I.getSize() == 640 * 480);
228 
229  vpDetectorAprilTag apriltag_detector(family);
230 
231  for (auto method : poseMethods) {
232  std::cout << "\tPose estimation method: " << method << std::endl;
233  apriltag_detector.setAprilTagPoseEstimationMethod(method);
234 
235  // Same tags size
236  {
237  std::vector<vpHomogeneousMatrix> cMo_vec;
238  apriltag_detector.detect(I, tagSize, cam, cMo_vec);
239  CHECK(cMo_vec.size() == nbTags);
240 
241  std::vector<std::vector<vpImagePoint> > tagsCorners = apriltag_detector.getPolygon();
242  CHECK(tagsCorners.size() == nbTags);
243 
244  std::vector<std::string> messages = apriltag_detector.getMessage();
245  CHECK(messages.size() == nbTags);
246 
247  std::vector<int> tagsId = apriltag_detector.getTagsId();
248  CHECK(tagsId.size() == nbTags);
249  std::map<int, int> idsCount;
250  for (size_t i = 0; i < tagsId.size(); i++) {
251  idsCount[tagsId[i]]++;
252  CHECK((tagsId[i] >= 0 && tagsId[i] < 5));
253  }
254  CHECK(idsCount.size() == nbTags);
255 
256  for (size_t i = 0; i < cMo_vec.size(); i++) {
257  const vpHomogeneousMatrix &cMo = cMo_vec[i];
258  const vpPoseVector pose(cMo);
259  int id = tagsId[i];
260  if (id >= 3) {
261  continue;
262  }
263  std::cout << "\t\tSame size, Tag: " << i << std::endl;
264  const vpHomogeneousMatrix &cMo_truth = groundTruthPoses[id];
265  const vpPoseVector pose_truth(cMo_truth);
266 
267  vpColVector error_translation = vpColVector(pose.getTranslationVector() - pose_truth.getTranslationVector());
268  vpColVector error_thetau = vpColVector(pose.getThetaUVector()) - vpColVector(pose_truth.getThetaUVector());
269  double error_trans = sqrt(error_translation.sumSquare() / 3);
270  double error_orientation = sqrt(error_thetau.sumSquare() / 3);
271  std::cout << "\t\t\tTranslation error: " << error_trans << " / Rotation error: " << error_orientation
272  << std::endl;
273  CHECK((error_trans < errorTranslationThresh[id] && error_orientation < errorRotationThresh[id]));
274  }
275  }
276 
277  // Custom tags size
278  {
279  apriltag_detector.detect(I);
280 
281  std::vector<std::vector<vpImagePoint> > tagsCorners = apriltag_detector.getPolygon();
282  CHECK(tagsCorners.size() == nbTags);
283 
284  std::vector<std::string> messages = apriltag_detector.getMessage();
285  CHECK(messages.size() == nbTags);
286 
287  std::vector<int> tagsId = apriltag_detector.getTagsId();
288  CHECK(tagsId.size() == nbTags);
289  std::map<int, int> idsCount;
290  for (size_t i = 0; i < tagsId.size(); i++) {
291  idsCount[tagsId[i]]++;
292  CHECK((tagsId[i] >= 0 && tagsId[i] < 5));
293  }
294  CHECK(idsCount.size() == nbTags);
295 
296  for (size_t idx = 0; idx < tagsId.size(); idx++) {
297  std::cout << "\t\tCustom size, Tag: " << idx << std::endl;
298  const int id = tagsId[idx];
300  apriltag_detector.getPose(idx, tagsSize[id] * tagSizeScales[family], cam, cMo);
301 
302  const vpPoseVector pose(cMo);
303  const vpHomogeneousMatrix &cMo_truth = groundTruthPoses[id];
304  const vpPoseVector pose_truth(cMo_truth);
305 
306  vpColVector error_translation = vpColVector(pose.getTranslationVector() - pose_truth.getTranslationVector());
307  vpColVector error_thetau = vpColVector(pose.getThetaUVector()) - vpColVector(pose_truth.getThetaUVector());
308  double error_trans = sqrt(error_translation.sumSquare() / 3);
309  double error_orientation = sqrt(error_thetau.sumSquare() / 3);
310  std::cout << "\t\t\tTranslation error: " << error_trans << " / Rotation error: " << error_orientation
311  << std::endl;
312  if (std::find(ignoreTests.begin(), ignoreTests.end(),
313  FailedTestCase(family, method, static_cast<int>(idx))) == ignoreTests.end()) {
314  CHECK((error_trans < errorTranslationThresh[id] && error_orientation < errorRotationThresh[id]));
315  }
316  }
317  }
318 
319  // Custom tags size + aligned Z-axis
320  {
321  apriltag_detector.detect(I);
322 
323  std::vector<std::vector<vpImagePoint> > tagsCorners = apriltag_detector.getPolygon();
324  CHECK(tagsCorners.size() == nbTags);
325 
326  std::vector<std::string> messages = apriltag_detector.getMessage();
327  CHECK(messages.size() == nbTags);
328 
329  std::vector<int> tagsId = apriltag_detector.getTagsId();
330  CHECK(tagsId.size() == nbTags);
331  std::map<int, int> idsCount;
332  for (size_t i = 0; i < tagsId.size(); i++) {
333  idsCount[tagsId[i]]++;
334  CHECK((tagsId[i] >= 0 && tagsId[i] < 5));
335  }
336  CHECK(idsCount.size() == nbTags);
337 
338  for (size_t idx = 0; idx < tagsId.size(); idx++) {
339  std::cout << "\t\tCustom size + aligned Z-axis, Tag: " << idx << std::endl;
340  const int id = tagsId[idx];
342  apriltag_detector.setZAlignedWithCameraAxis(true);
343  apriltag_detector.getPose(idx, tagsSize[id] * tagSizeScales[family], cam, cMo);
344  apriltag_detector.setZAlignedWithCameraAxis(false);
345 
346  const vpPoseVector pose(cMo);
347  const vpHomogeneousMatrix oMo2(vpTranslationVector(), vpThetaUVector(M_PI, 0, 0));
348  const vpHomogeneousMatrix cMo_truth = groundTruthPoses[id] * oMo2;
349  const vpPoseVector pose_truth(cMo_truth);
350 
351  vpColVector error_translation = vpColVector(pose.getTranslationVector() - pose_truth.getTranslationVector());
352  vpColVector error_thetau = vpColVector(pose.getThetaUVector()) - vpColVector(pose_truth.getThetaUVector());
353  double error_trans = sqrt(error_translation.sumSquare() / 3);
354  double error_orientation = sqrt(error_thetau.sumSquare() / 3);
355  std::cout << "\t\t\tTranslation error: " << error_trans << " / Rotation error: " << error_orientation
356  << std::endl;
357  if (std::find(ignoreTests.begin(), ignoreTests.end(),
358  FailedTestCase(family, method, static_cast<int>(idx))) == ignoreTests.end()) {
359  CHECK((error_trans < errorTranslationThresh[id] && error_orientation < errorRotationThresh[id]));
360  }
361  }
362  }
363  }
364  }
365 }
366 
367 TEST_CASE("Apriltag corners accuracy test", "[apriltag_corners_accuracy_test]")
368 {
369  std::map<vpDetectorAprilTag::vpAprilTagFamily, std::string> apriltagMap = {
370  {vpDetectorAprilTag::TAG_16h5, "tag16_05"},
371  {vpDetectorAprilTag::TAG_25h9, "tag25_09"},
372  {vpDetectorAprilTag::TAG_36h11, "tag36_11"},
374 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
375  ,
380 #endif
381  };
382 
383  const size_t nbTags = 5;
384  std::map<vpDetectorAprilTag::vpAprilTagFamily, std::map<int, std::vector<vpImagePoint> > > groundTruthCorners;
385  for (const auto &kv : apriltagMap) {
386  std::string filename =
388  std::string("AprilTag/benchmark/640x480/corners_") + kv.second + std::string(".txt"));
389  std::ifstream file(filename);
390  REQUIRE(file.is_open());
391 
392  int id = 0;
393  double p0x = 0, p0y = 0;
394  double p1x = 0, p1y = 0;
395  double p2x = 0, p2y = 0;
396  double p3x = 0, p3y = 0;
397  while (file >> id >> p0x >> p0y >> p1x >> p1y >> p2x >> p2y >> p3x >> p3y) {
398  groundTruthCorners[kv.first][id].push_back(vpImagePoint(p0y, p0x));
399  groundTruthCorners[kv.first][id].push_back(vpImagePoint(p1y, p1x));
400  groundTruthCorners[kv.first][id].push_back(vpImagePoint(p2y, p2x));
401  groundTruthCorners[kv.first][id].push_back(vpImagePoint(p3y, p3x));
402  REQUIRE(groundTruthCorners[kv.first][id].size() == 4);
403  }
404  }
405 
406  for (const auto &kv : apriltagMap) {
407  auto family = kv.first;
408  std::cout << "\nApriltag family: " << family << std::endl;
409  std::string filename =
411  std::string("AprilTag/benchmark/640x480/") + kv.second + std::string("_640x480.png"));
412  REQUIRE(vpIoTools::checkFilename(filename));
413 
415  vpImageIo::read(I, filename);
416  REQUIRE(I.getSize() == 640 * 480);
417 
418  vpDetectorAprilTag apriltag_detector(family);
419  apriltag_detector.detect(I);
420  std::vector<int> tagsId = apriltag_detector.getTagsId();
421  std::vector<std::vector<vpImagePoint> > tagsCorners = apriltag_detector.getTagsCorners();
422 
423  REQUIRE(tagsCorners.size() == nbTags);
424  REQUIRE(tagsId.size() == nbTags);
425  for (size_t i = 0; i < tagsCorners.size(); i++) {
426  const int tagId = tagsId[i];
427  REQUIRE(tagsCorners[i].size() == 4);
428 
429  TagGroundTruth corners_ref("", groundTruthCorners[family][tagId]);
430  TagGroundTruth corners_cur("", tagsCorners[i]);
431  CHECK((corners_ref == corners_cur));
432 
433  std::cout << "\tid: " << tagId << " - RMSE: " << corners_ref.rmse(corners_cur.m_corners) << std::endl;
434  }
435  }
436 }
437 
438 #if defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_EIGEN3)
439 TEST_CASE("Apriltag regression test", "[apriltag_regression_test]")
440 {
441 #if (VISP_HAVE_DATASET_VERSION >= 0x030600)
442  const std::string filename = vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "AprilTag/AprilTag.png");
443 #else
444  const std::string filename = vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "AprilTag/AprilTag.pgm");
445 #endif
446  REQUIRE(vpIoTools::checkFilename(filename));
447 
449  vpImageIo::read(I, filename);
450  REQUIRE(I.getSize() == 640 * 480);
451 
454  const double tagSize = 0.053;
455  const float quad_decimate = 1.0;
456  vpDetectorBase *detector = new vpDetectorAprilTag(tagFamily);
457  dynamic_cast<vpDetectorAprilTag *>(detector)->setAprilTagQuadDecimate(quad_decimate);
458  dynamic_cast<vpDetectorAprilTag *>(detector)->setAprilTagPoseEstimationMethod(poseEstimationMethod);
459 
460  vpCameraParameters cam;
461  cam.initPersProjWithoutDistortion(615.1674805, 615.1675415, 312.1889954, 243.4373779);
462 
463  std::vector<vpHomogeneousMatrix> cMo_vec;
464  dynamic_cast<vpDetectorAprilTag *>(detector)->detect(I, tagSize, cam, cMo_vec);
465 
466  // Ground truth
467  std::map<std::string, TagGroundTruth> mapOfTagsGroundTruth;
468  {
469  std::string filename_ground_truth =
470  vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "AprilTag/ground_truth_detection.txt");
471  std::ifstream file_ground_truth(filename_ground_truth.c_str());
472  REQUIRE(file_ground_truth.is_open());
473  std::string message = "";
474  double v1 = 0.0, v2 = 0.0, v3 = 0.0, v4 = 0.0;
475  double u1 = 0.0, u2 = 0.0, u3 = 0.0, u4 = 0.0;
476  while (file_ground_truth >> message >> v1 >> u1 >> v2 >> u2 >> v3 >> u3 >> v4 >> u4) {
477  std::vector<vpImagePoint> tagCorners(4);
478  tagCorners[0].set_ij(v1, u1);
479  tagCorners[1].set_ij(v2, u2);
480  tagCorners[2].set_ij(v3, u3);
481  tagCorners[3].set_ij(v4, u4);
482  mapOfTagsGroundTruth.insert(std::make_pair(message, TagGroundTruth(message, tagCorners)));
483  }
484  }
485 
486  std::map<std::string, vpPoseVector> mapOfPosesGroundTruth;
487  {
488  std::string filename_ground_truth =
489  vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "AprilTag/ground_truth_pose.txt");
490  std::ifstream file_ground_truth(filename_ground_truth.c_str());
491  REQUIRE(file_ground_truth.is_open());
492  std::string message = "";
493  double tx = 0.0, ty = 0.0, tz = 0.0;
494  double tux = 0.0, tuy = 0.0, tuz = 0.0;
495  while (file_ground_truth >> message >> tx >> ty >> tz >> tux >> tuy >> tuz) {
496  mapOfPosesGroundTruth.insert(std::make_pair(message, vpPoseVector(tx, ty, tz, tux, tuy, tuz)));
497  }
498  }
499 
500  for (size_t i = 0; i < detector->getNbObjects(); i++) {
501  std::vector<vpImagePoint> p = detector->getPolygon(i);
502 
503  std::string message = detector->getMessage(i);
504  std::replace(message.begin(), message.end(), ' ', '_');
505  std::map<std::string, TagGroundTruth>::iterator it = mapOfTagsGroundTruth.find(message);
506  TagGroundTruth current(message, p);
507  if (it == mapOfTagsGroundTruth.end()) {
508  std::cerr << "Problem with tag decoding (tag_family or id): " << message << std::endl;
509  }
510  else if (it->second != current) {
511  std::cerr << "Problem, current detection:\n" << current << "\nReference:\n" << it->second << std::endl;
512  }
513  REQUIRE(it != mapOfTagsGroundTruth.end());
514  CHECK(it->second == current);
515  }
516 
517  for (size_t i = 0; i < cMo_vec.size(); i++) {
518  vpPoseVector pose_vec(cMo_vec[i]);
519 
520  std::string message = detector->getMessage(i);
521  std::replace(message.begin(), message.end(), ' ', '_');
522  std::map<std::string, vpPoseVector>::iterator it = mapOfPosesGroundTruth.find(message);
523  if (it == mapOfPosesGroundTruth.end()) {
524  std::cerr << "Problem with tag decoding (tag_family or id): " << message << std::endl;
525  }
526  REQUIRE(it != mapOfPosesGroundTruth.end());
527  std::cout << "Tag: " << message << std::endl;
528  std::cout << "\tEstimated pose: " << pose_vec.t() << std::endl;
529  std::cout << "\tReference pose: " << it->second.t() << std::endl;
530  for (unsigned int cpt = 0; cpt < 3; cpt++) {
531  if (!vpMath::equal(it->second[cpt], pose_vec[cpt], 0.005) ||
532  !vpMath::equal(it->second[cpt + 3], pose_vec[cpt + 3], 0.005)) {
533  std::cerr << "Problem, current pose: " << pose_vec.t() << "\nReference pose: " << it->second.t() << std::endl;
534  }
535  CHECK((vpMath::equal(it->second[cpt], pose_vec[cpt], 0.005) &&
536  vpMath::equal(it->second[cpt + 3], pose_vec[cpt + 3], 0.005)));
537  }
538  }
539 
540  delete detector;
541 }
542 
543 TEST_CASE("Apriltag copy constructor test", "[apriltag_copy_constructor_test]")
544 {
545  const std::string filename =
546  vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "AprilTag/benchmark/640x480/tag21_07_640x480.png");
547  REQUIRE(vpIoTools::checkFilename(filename));
548 
550  vpImageIo::read(I, filename);
551  REQUIRE(I.getSize() == 640 * 480);
552 
555  const double tagSize = 0.25 * 5 / 9;
556  const float quad_decimate = 1.0;
557  vpDetectorAprilTag *detector = new vpDetectorAprilTag(tagFamily, poseEstimationMethod);
558  detector->setAprilTagQuadDecimate(quad_decimate);
559 
560  vpCameraParameters cam;
561  cam.initPersProjWithoutDistortion(700, 700, 320, 240);
562 
563  std::vector<vpHomogeneousMatrix> cMo_vec;
564  detector->detect(I, tagSize, cam, cMo_vec);
565  std::vector<std::vector<vpImagePoint> > tagsCorners = detector->getTagsCorners();
566  std::vector<int> tagsId = detector->getTagsId();
567 
568  // Copy
569  vpDetectorAprilTag detector_copy(*detector);
570  // Delete old detector
571  delete detector;
572 
573  std::vector<std::vector<vpImagePoint> > tagsCorners_copy = detector_copy.getTagsCorners();
574  std::vector<int> tagsId_copy = detector_copy.getTagsId();
575  REQUIRE(tagsCorners_copy.size() == tagsCorners.size());
576  REQUIRE(tagsId_copy.size() == tagsId.size());
577  REQUIRE(tagsCorners_copy.size() == tagsId_copy.size());
578 
579  for (size_t i = 0; i < tagsCorners.size(); i++) {
580  const std::vector<vpImagePoint> &corners_ref = tagsCorners[i];
581  const std::vector<vpImagePoint> &corners_copy = tagsCorners_copy[i];
582  REQUIRE(corners_ref.size() == corners_copy.size());
583 
584  for (size_t j = 0; j < corners_ref.size(); j++) {
585  const vpImagePoint &corner_ref = corners_ref[j];
586  const vpImagePoint &corner_copy = corners_copy[j];
587  CHECK(corner_ref == corner_copy);
588  }
589 
590  int id_ref = tagsId[i];
591  int id_copy = tagsId_copy[i];
592  CHECK(id_ref == id_copy);
593  }
594 
595  std::vector<vpHomogeneousMatrix> cMo_vec_copy;
596  detector_copy.detect(I, tagSize, cam, cMo_vec_copy);
597  REQUIRE(cMo_vec.size() == cMo_vec_copy.size());
598  for (size_t idx = 0; idx < cMo_vec_copy.size(); idx++) {
599  const vpHomogeneousMatrix &cMo = cMo_vec[idx];
600  const vpHomogeneousMatrix &cMo_copy = cMo_vec_copy[idx];
601  for (unsigned int i = 0; i < 3; i++) {
602  for (unsigned int j = 0; j < 4; j++) {
603  CHECK(vpMath::equal(cMo[i][j], cMo_copy[i][j], std::numeric_limits<double>::epsilon()));
604  }
605  }
606  }
607 }
608 
609 TEST_CASE("Apriltag assignment operator test", "[apriltag_assignment_operator_test]")
610 {
611  const std::string filename =
612  vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "AprilTag/benchmark/640x480/tag21_07_640x480.png");
613  REQUIRE(vpIoTools::checkFilename(filename));
614 
616  vpImageIo::read(I, filename);
617  REQUIRE(I.getSize() == 640 * 480);
618 
621  const double tagSize = 0.25 * 5 / 9;
622  const float quad_decimate = 1.0;
623  vpDetectorAprilTag *detector = new vpDetectorAprilTag(tagFamily, poseEstimationMethod);
624  detector->setAprilTagQuadDecimate(quad_decimate);
625 
626  vpCameraParameters cam;
627  cam.initPersProjWithoutDistortion(700, 700, 320, 240);
628 
629  std::vector<vpHomogeneousMatrix> cMo_vec;
630  detector->detect(I, tagSize, cam, cMo_vec);
631  std::vector<std::vector<vpImagePoint> > tagsCorners = detector->getTagsCorners();
632  std::vector<int> tagsId = detector->getTagsId();
633 
634  // Copy
635  vpDetectorAprilTag detector_copy = *detector;
636  // Delete old detector
637  delete detector;
638 
639  std::vector<std::vector<vpImagePoint> > tagsCorners_copy = detector_copy.getTagsCorners();
640  std::vector<int> tagsId_copy = detector_copy.getTagsId();
641  REQUIRE(tagsCorners_copy.size() == tagsCorners.size());
642  REQUIRE(tagsId_copy.size() == tagsId.size());
643  REQUIRE(tagsCorners_copy.size() == tagsId_copy.size());
644 
645  for (size_t i = 0; i < tagsCorners.size(); i++) {
646  const std::vector<vpImagePoint> &corners_ref = tagsCorners[i];
647  const std::vector<vpImagePoint> &corners_copy = tagsCorners_copy[i];
648  REQUIRE(corners_ref.size() == corners_copy.size());
649 
650  for (size_t j = 0; j < corners_ref.size(); j++) {
651  const vpImagePoint &corner_ref = corners_ref[j];
652  const vpImagePoint &corner_copy = corners_copy[j];
653  CHECK(corner_ref == corner_copy);
654  }
655 
656  int id_ref = tagsId[i];
657  int id_copy = tagsId_copy[i];
658  CHECK(id_ref == id_copy);
659  }
660 
661  std::vector<vpHomogeneousMatrix> cMo_vec_copy;
662  detector_copy.detect(I, tagSize, cam, cMo_vec_copy);
663  REQUIRE(cMo_vec.size() == cMo_vec_copy.size());
664  for (size_t idx = 0; idx < cMo_vec_copy.size(); idx++) {
665  const vpHomogeneousMatrix &cMo = cMo_vec[idx];
666  const vpHomogeneousMatrix &cMo_copy = cMo_vec_copy[idx];
667  for (unsigned int i = 0; i < 3; i++) {
668  for (unsigned int j = 0; j < 4; j++) {
669  CHECK(vpMath::equal(cMo[i][j], cMo_copy[i][j], std::numeric_limits<double>::epsilon()));
670  }
671  }
672  }
673 }
674 
675 TEST_CASE("Apriltag getTagsPoints3D test", "[apriltag_get_tags_points3D_test]")
676 {
677  const std::string filename =
678  vpIoTools::createFilePath(vpIoTools::getViSPImagesDataPath(), "AprilTag/benchmark/640x480/tag21_07_640x480.png");
679  REQUIRE(vpIoTools::checkFilename(filename));
680 
682  vpImageIo::read(I, filename);
683  REQUIRE(I.getSize() == 640 * 480);
684 
687  const double familyScale = 5.0 / 9;
688  const double tagSize = 0.25;
689  std::map<int, double> tagsSize = {
690  {-1, tagSize * familyScale}, {3, tagSize / 2 * familyScale}, {4, tagSize / 2 * familyScale} };
691 
692  vpDetectorAprilTag detector(tagFamily, poseEstimationMethod);
693 
694  vpCameraParameters cam;
695  cam.initPersProjWithoutDistortion(700, 700, 320, 240);
696 
697  std::vector<vpHomogeneousMatrix> cMo_vec;
698  REQUIRE(detector.detect(I));
699 
700  // Compute pose with getPose
701  std::vector<int> tagsId = detector.getTagsId();
702  for (size_t i = 0; i < tagsId.size(); i++) {
703  int id = tagsId[i];
704  double size = tagsSize[-1];
705  if (tagsSize.find(id) != tagsSize.end()) {
706  size = tagsSize[id];
707  }
708 
710  detector.getPose(i, size, cam, cMo);
711  cMo_vec.push_back(cMo);
712  }
713 
714  // Compute pose manually
715  std::vector<std::vector<vpPoint> > tagsPoints = detector.getTagsPoints3D(tagsId, tagsSize);
716  std::vector<std::vector<vpImagePoint> > tagsCorners = detector.getTagsCorners();
717  REQUIRE(tagsPoints.size() == tagsCorners.size());
718 
719  for (size_t i = 0; i < tagsPoints.size(); i++) {
720  REQUIRE(tagsPoints[i].size() == tagsCorners[i].size());
721 
722  for (size_t j = 0; j < tagsPoints[i].size(); j++) {
723  vpPoint &pt = tagsPoints[i][j];
724  const vpImagePoint &imPt = tagsCorners[i][j];
725  double x = 0, y = 0;
726  vpPixelMeterConversion::convertPoint(cam, imPt, x, y);
727  pt.set_x(x);
728  pt.set_y(y);
729  }
730 
731  vpPose pose(tagsPoints[i]);
732  vpHomogeneousMatrix cMo_manual;
733  pose.computePose(vpPose::DEMENTHON_LAGRANGE_VIRTUAL_VS, cMo_manual);
734 
735  const vpHomogeneousMatrix &cMo = cMo_vec[i];
736  // Note that using epsilon = std::numeric_limits<double>::epsilon() makes this test
737  // failing on Ubuntu 18.04 when none of the Lapack 3rd party libraries, nor the built-in are used.
738  // Admissible espilon value is 1e-14. Using 1e-15 makes the test failing.
739  // Again on Debian i386 where Lapack is enable, using std::numeric_limits<double>::epsilon()
740  // makes this test failing.
741  double epsilon = 1e-12;
742 
743  for (unsigned int row = 0; row < cMo.getRows(); row++) {
744  for (unsigned int col = 0; col < cMo.getCols(); col++) {
745  CHECK(vpMath::equal(cMo[row][col], cMo_manual[row][col], epsilon));
746  }
747  }
748  }
749 }
750 #endif // #if defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_OPENCV) || defined(VISP_HAVE_EIGEN3)
751 
752 int main(int argc, const char *argv[])
753 {
754  Catch::Session session;
755 
756  session.applyCommandLine(argc, argv);
757  int numFailed = session.run();
758 
759  return numFailed;
760 }
761 
762 #else
763 int main() { return EXIT_SUCCESS; }
764 #endif
unsigned int getCols() const
Definition: vpArray2D.h:337
unsigned int getRows() const
Definition: vpArray2D.h:347
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
double sumSquare() const
std::vector< std::vector< vpImagePoint > > getTagsCorners() const
void setAprilTagQuadDecimate(float quadDecimate)
std::vector< std::vector< vpPoint > > getTagsPoints3D(const std::vector< int > &tagsId, const std::map< int, double > &tagsSize) const
bool detect(const vpImage< unsigned char > &I) VP_OVERRIDE
@ TAG_CIRCLE21h7
AprilTag Circle21h7 pattern.
@ TAG_25h9
AprilTag 25h9 pattern.
@ TAG_CUSTOM48h12
AprilTag Custom48h12 pattern.
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
@ TAG_STANDARD52h13
AprilTag Standard52h13 pattern.
@ TAG_16h5
AprilTag 16h5 pattern.
@ TAG_STANDARD41h12
AprilTag Standard41h12 pattern.
@ TAG_CIRCLE49h12
AprilTag Circle49h12 pattern.
std::vector< int > getTagsId() const
bool getPose(size_t tagIndex, double tagSize, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, vpHomogeneousMatrix *cMo2=nullptr, double *projError=nullptr, double *projError2=nullptr)
std::vector< std::vector< vpImagePoint > > & getPolygon()
size_t getNbObjects() const
std::vector< std::string > & getMessage()
Implementation of an homogeneous matrix and operations on such kind of matrices.
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition: vpImageIo.cpp:147
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
double get_j() const
Definition: vpImagePoint.h:125
double get_i() const
Definition: vpImagePoint.h:114
unsigned int getSize() const
Definition: vpImage.h:221
static std::string getViSPImagesDataPath()
Definition: vpIoTools.cpp:1053
static bool checkFilename(const std::string &filename)
Definition: vpIoTools.cpp:786
static std::string createFilePath(const std::string &parent, const std::string &child)
Definition: vpIoTools.cpp:1427
static bool equal(double x, double y, double threshold=0.001)
Definition: vpMath.h:459
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_x(double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.cpp:464
void set_y(double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.cpp:466
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition: vpPose.h:77
@ DEMENTHON_LAGRANGE_VIRTUAL_VS
Definition: vpPose.h:98
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.