Visual Servoing Platform  version 3.5.1 under development (2022-08-17)
vpDetectorAprilTag.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  * Base class for April Tag detection.
33  *
34  *****************************************************************************/
35 #include <visp3/core/vpConfig.h>
36 
37 #ifdef VISP_HAVE_APRILTAG
38 #include <map>
39 
40 #include <apriltag.h>
41 #include <apriltag_pose.h>
42 #include <common/homography.h>
43 #include <tag16h5.h>
44 #include <tag25h7.h>
45 #include <tag25h9.h>
46 #include <tag36h10.h>
47 #include <tag36h11.h>
48 #include <tagCircle21h7.h>
49 #include <tagStandard41h12.h>
50 #include <visp3/detection/vpDetectorAprilTag.h>
51 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
52 #include <tagCircle49h12.h>
53 #include <tagCustom48h12.h>
54 #include <tagStandard41h12.h>
55 #include <tagStandard52h13.h>
56 #endif
57 
58 #include <visp3/core/vpDisplay.h>
59 #include <visp3/core/vpPixelMeterConversion.h>
60 #include <visp3/core/vpPoint.h>
61 #include <visp3/vision/vpPose.h>
62 
63 #ifndef DOXYGEN_SHOULD_SKIP_THIS
64 class vpDetectorAprilTag::Impl
65 {
66 public:
67  Impl(const vpAprilTagFamily &tagFamily, const vpPoseEstimationMethod &method)
68  : m_poseEstimationMethod(method), m_tagsId(), m_tagFamily(tagFamily), m_td(NULL), m_tf(NULL), m_detections(NULL),
69  m_zAlignedWithCameraFrame(false)
70  {
71  switch (m_tagFamily) {
72  case TAG_36h11:
73  m_tf = tag36h11_create();
74  break;
75 
76  case TAG_36h10:
77  m_tf = tag36h10_create();
78  break;
79 
80  case TAG_36ARTOOLKIT:
81  break;
82 
83  case TAG_25h9:
84  m_tf = tag25h9_create();
85  break;
86 
87  case TAG_25h7:
88  m_tf = tag25h7_create();
89  break;
90 
91  case TAG_16h5:
92  m_tf = tag16h5_create();
93  break;
94 
95  case TAG_CIRCLE21h7:
96  m_tf = tagCircle21h7_create();
97  break;
98 
99  case TAG_CIRCLE49h12:
100 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
101  m_tf = tagCircle49h12_create();
102 #endif
103  break;
104 
105  case TAG_CUSTOM48h12:
106 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
107  m_tf = tagCustom48h12_create();
108 #endif
109  break;
110 
111  case TAG_STANDARD52h13:
112 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
113  m_tf = tagStandard52h13_create();
114 #endif
115  break;
116 
117  case TAG_STANDARD41h12:
118 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
119  m_tf = tagStandard41h12_create();
120 #endif
121  break;
122 
123  default:
124  throw vpException(vpException::fatalError, "Unknown Tag family!");
125  }
126 
127  if (m_tagFamily != TAG_36ARTOOLKIT && m_tf) {
128  m_td = apriltag_detector_create();
129  apriltag_detector_add_family(m_td, m_tf);
130  }
131 
132  m_mapOfCorrespondingPoseMethods[DEMENTHON_VIRTUAL_VS] = vpPose::DEMENTHON;
133  m_mapOfCorrespondingPoseMethods[LAGRANGE_VIRTUAL_VS] = vpPose::LAGRANGE;
134  }
135 
136  Impl(const Impl &o)
137  : m_poseEstimationMethod(o.m_poseEstimationMethod), m_tagsId(o.m_tagsId), m_tagFamily(o.m_tagFamily), m_td(NULL),
138  m_tf(NULL), m_detections(NULL), m_zAlignedWithCameraFrame(o.m_zAlignedWithCameraFrame)
139  {
140  switch (m_tagFamily) {
141  case TAG_36h11:
142  m_tf = tag36h11_create();
143  break;
144 
145  case TAG_36h10:
146  m_tf = tag36h10_create();
147  break;
148 
149  case TAG_36ARTOOLKIT:
150  break;
151 
152  case TAG_25h9:
153  m_tf = tag25h9_create();
154  break;
155 
156  case TAG_25h7:
157  m_tf = tag25h7_create();
158  break;
159 
160  case TAG_16h5:
161  m_tf = tag16h5_create();
162  break;
163 
164  case TAG_CIRCLE21h7:
165  m_tf = tagCircle21h7_create();
166  break;
167 
168  case TAG_CIRCLE49h12:
169 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
170  m_tf = tagCircle49h12_create();
171 #endif
172  break;
173 
174  case TAG_CUSTOM48h12:
175 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
176  m_tf = tagCustom48h12_create();
177 #endif
178  break;
179 
180  case TAG_STANDARD52h13:
181 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
182  m_tf = tagStandard52h13_create();
183 #endif
184  break;
185 
186  case TAG_STANDARD41h12:
187 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
188  m_tf = tagStandard41h12_create();
189 #endif
190  break;
191 
192  default:
193  throw vpException(vpException::fatalError, "Unknown Tag family!");
194  }
195 
196  if (m_tagFamily != TAG_36ARTOOLKIT && m_tf) {
197  m_td = apriltag_detector_create();
198  apriltag_detector_add_family(m_td, m_tf);
199  }
200 
201  m_mapOfCorrespondingPoseMethods[DEMENTHON_VIRTUAL_VS] = vpPose::DEMENTHON;
202  m_mapOfCorrespondingPoseMethods[LAGRANGE_VIRTUAL_VS] = vpPose::LAGRANGE;
203 
204  if (o.m_detections != NULL) {
205  m_detections = apriltag_detections_copy(o.m_detections);
206  }
207  }
208 
209  ~Impl()
210  {
211  if (m_td) {
212  apriltag_detector_destroy(m_td);
213  }
214 
215  if (m_tf) {
216  switch (m_tagFamily) {
217  case TAG_36h11:
218  tag36h11_destroy(m_tf);
219  break;
220 
221  case TAG_36h10:
222  tag36h10_destroy(m_tf);
223  break;
224 
225  case TAG_36ARTOOLKIT:
226  break;
227 
228  case TAG_25h9:
229  tag25h9_destroy(m_tf);
230  break;
231 
232  case TAG_25h7:
233  tag25h7_destroy(m_tf);
234  break;
235 
236  case TAG_16h5:
237  tag16h5_destroy(m_tf);
238  break;
239 
240  case TAG_CIRCLE21h7:
241  tagCircle21h7_destroy(m_tf);
242  break;
243 
244  case TAG_CIRCLE49h12:
245 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
246  tagCustom48h12_destroy(m_tf);
247 #endif
248  break;
249 
250  case TAG_CUSTOM48h12:
251 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
252  tagCustom48h12_destroy(m_tf);
253 #endif
254  break;
255 
256  case TAG_STANDARD52h13:
257 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
258  tagStandard52h13_destroy(m_tf);
259 #endif
260  break;
261 
262  case TAG_STANDARD41h12:
263 #if defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
264  tagStandard41h12_destroy(m_tf);
265 #endif
266  break;
267 
268  default:
269  break;
270  }
271  }
272 
273  if (m_detections) {
274  apriltag_detections_destroy(m_detections);
275  m_detections = NULL;
276  }
277  }
278 
279  void convertHomogeneousMatrix(const apriltag_pose_t &pose, vpHomogeneousMatrix &cMo)
280  {
281  for (unsigned int i = 0; i < 3; i++) {
282  for (unsigned int j = 0; j < 3; j++) {
283  cMo[i][j] = MATD_EL(pose.R, i, j);
284  }
285  cMo[i][3] = MATD_EL(pose.t, i, 0);
286  }
287  }
288 
289  bool detect(const vpImage<unsigned char> &I, double tagSize, const vpCameraParameters &cam,
290  std::vector<std::vector<vpImagePoint> > &polygons, std::vector<std::string> &messages, bool displayTag,
291  const vpColor color, unsigned int thickness, std::vector<vpHomogeneousMatrix> *cMo_vec,
292  std::vector<vpHomogeneousMatrix> *cMo_vec2, std::vector<double> *projErrors,
293  std::vector<double> *projErrors2)
294  {
295  if (m_tagFamily == TAG_36ARTOOLKIT) {
296  // TAG_36ARTOOLKIT is not available anymore
297  std::cerr << "TAG_36ARTOOLKIT detector is not available anymore." << std::endl;
298  return false;
299  }
300 #if !defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
303  std::cerr << "TAG_CIRCLE49h12, TAG_CUSTOM48h12, TAG_STANDARD41h12 and TAG_STANDARD52h13 are disabled."
304  << std::endl;
305  return false;
306  }
307 #endif
308 
309  const bool computePose = (cMo_vec != NULL);
310 
311  image_u8_t im = {/*.width =*/(int32_t)I.getWidth(),
312  /*.height =*/(int32_t)I.getHeight(),
313  /*.stride =*/(int32_t)I.getWidth(),
314  /*.buf =*/I.bitmap};
315 
316  if (m_detections) {
317  apriltag_detections_destroy(m_detections);
318  m_detections = NULL;
319  }
320 
321  m_detections = apriltag_detector_detect(m_td, &im);
322  int nb_detections = zarray_size(m_detections);
323  bool detected = nb_detections > 0;
324 
325  polygons.resize(static_cast<size_t>(nb_detections));
326  messages.resize(static_cast<size_t>(nb_detections));
327  m_tagsId.resize(static_cast<size_t>(nb_detections));
328 
329  for (int i = 0; i < zarray_size(m_detections); i++) {
330  apriltag_detection_t *det;
331  zarray_get(m_detections, i, &det);
332 
333  std::vector<vpImagePoint> polygon;
334  for (int j = 0; j < 4; j++) {
335  polygon.push_back(vpImagePoint(det->p[j][1], det->p[j][0]));
336  }
337  polygons[static_cast<size_t>(i)] = polygon;
338  std::stringstream ss;
339  ss << m_tagFamily << " id: " << det->id;
340  messages[static_cast<size_t>(i)] = ss.str();
341  m_tagsId[static_cast<size_t>(i)] = det->id;
342 
343  if (displayTag) {
344  vpColor Ox = (color == vpColor::none) ? vpColor::red : color;
345  vpColor Oy = (color == vpColor::none) ? vpColor::green : color;
346  vpColor Ox2 = (color == vpColor::none) ? vpColor::yellow : color;
347  vpColor Oy2 = (color == vpColor::none) ? vpColor::blue : color;
348 
349  vpDisplay::displayLine(I, (int)det->p[0][1], (int)det->p[0][0], (int)det->p[1][1], (int)det->p[1][0], Ox,
350  thickness);
351  vpDisplay::displayLine(I, (int)det->p[0][1], (int)det->p[0][0], (int)det->p[3][1], (int)det->p[3][0], Oy,
352  thickness);
353  vpDisplay::displayLine(I, (int)det->p[1][1], (int)det->p[1][0], (int)det->p[2][1], (int)det->p[2][0], Ox2,
354  thickness);
355  vpDisplay::displayLine(I, (int)det->p[2][1], (int)det->p[2][0], (int)det->p[3][1], (int)det->p[3][0], Oy2,
356  thickness);
357  }
358 
359  if (computePose) {
360  vpHomogeneousMatrix cMo, cMo2;
361  double err1, err2;
362  if (getPose(static_cast<size_t>(i), tagSize, cam, cMo, cMo_vec2 ? &cMo2 : NULL, projErrors ? &err1 : NULL,
363  projErrors2 ? &err2 : NULL)) {
364  cMo_vec->push_back(cMo);
365  if (cMo_vec2) {
366  cMo_vec2->push_back(cMo2);
367  }
368  if (projErrors) {
369  projErrors->push_back(err1);
370  }
371  if (projErrors2) {
372  projErrors2->push_back(err2);
373  }
374  }
375  // else case should never happen
376  }
377  }
378 
379  return detected;
380  }
381 
382  bool getPose(size_t tagIndex, double tagSize, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo,
383  vpHomogeneousMatrix *cMo2, double *projErrors, double *projErrors2)
384  {
385  if (m_detections == NULL) {
386  throw(vpException(vpException::fatalError, "Cannot get tag index=%d pose: detection empty", tagIndex));
387  }
388  if (m_tagFamily == TAG_36ARTOOLKIT) {
389  // TAG_36ARTOOLKIT is not available anymore
390  std::cerr << "TAG_36ARTOOLKIT detector is not available anymore." << std::endl;
391  return false;
392  }
393 #if !defined(VISP_HAVE_APRILTAG_BIG_FAMILY)
396  std::cerr << "TAG_CIRCLE49h12, TAG_CUSTOM48h12, TAG_STANDARD41h12 and TAG_STANDARD52h13 are disabled."
397  << std::endl;
398  return false;
399  }
400 #endif
401 
402  apriltag_detection_t *det;
403  zarray_get(m_detections, static_cast<int>(tagIndex), &det);
404 
405  int nb_detections = zarray_size(m_detections);
406  if (tagIndex >= (size_t)nb_detections) {
407  return false;
408  }
409 
410  // In AprilTag3, estimate_pose_for_tag_homography() and estimate_tag_pose() have been added.
411  // They use a tag frame aligned with the camera frame
412  // Before the release of AprilTag3, convention used was to define the z-axis of the tag going upward.
413  // To keep compatibility, we maintain the same convention than before and there is setZAlignedWithCameraAxis().
414  // Under the hood, we use aligned frames everywhere and transform the pose according to the option.
415 
416  vpHomogeneousMatrix cMo_homography_ortho_iter;
419  double fx = cam.get_px(), fy = cam.get_py();
420  double cx = cam.get_u0(), cy = cam.get_v0();
421 
422  apriltag_detection_info_t info;
423  info.det = det;
424  info.tagsize = tagSize;
425  info.fx = fx;
426  info.fy = fy;
427  info.cx = cx;
428  info.cy = cy;
429 
430  // projErrors and projErrors2 will be override later
431  getPoseWithOrthogonalMethod(info, cMo, cMo2, projErrors, projErrors2);
432  cMo_homography_ortho_iter = cMo;
433  }
434 
435  vpHomogeneousMatrix cMo_homography;
438  double fx = cam.get_px(), fy = cam.get_py();
439  double cx = cam.get_u0(), cy = cam.get_v0();
440 
441  apriltag_detection_info_t info;
442  info.det = det;
443  info.tagsize = tagSize;
444  info.fx = fx;
445  info.fy = fy;
446  info.cx = cx;
447  info.cy = cy;
448 
449  apriltag_pose_t pose;
450  estimate_pose_for_tag_homography(&info, &pose);
451  convertHomogeneousMatrix(pose, cMo);
452 
453  matd_destroy(pose.R);
454  matd_destroy(pose.t);
455 
456  cMo_homography = cMo;
457  }
458 
459  // Add marker object points
460  vpPose pose;
461  vpPoint pt;
462 
463  vpImagePoint imPt;
464  double x = 0.0, y = 0.0;
465  std::vector<vpPoint> pts(4);
466  pt.setWorldCoordinates(-tagSize / 2.0, tagSize / 2.0, 0.0);
467  imPt.set_uv(det->p[0][0], det->p[0][1]);
468  vpPixelMeterConversion::convertPoint(cam, imPt, x, y);
469  pt.set_x(x);
470  pt.set_y(y);
471  pts[0] = pt;
472 
473  pt.setWorldCoordinates(tagSize / 2.0, tagSize / 2.0, 0.0);
474  imPt.set_uv(det->p[1][0], det->p[1][1]);
475  vpPixelMeterConversion::convertPoint(cam, imPt, x, y);
476  pt.set_x(x);
477  pt.set_y(y);
478  pts[1] = pt;
479 
480  pt.setWorldCoordinates(tagSize / 2.0, -tagSize / 2.0, 0.0);
481  imPt.set_uv(det->p[2][0], det->p[2][1]);
482  vpPixelMeterConversion::convertPoint(cam, imPt, x, y);
483  pt.set_x(x);
484  pt.set_y(y);
485  pts[2] = pt;
486 
487  pt.setWorldCoordinates(-tagSize / 2.0, -tagSize / 2.0, 0.0);
488  imPt.set_uv(det->p[3][0], det->p[3][1]);
489  vpPixelMeterConversion::convertPoint(cam, imPt, x, y);
490  pt.set_x(x);
491  pt.set_y(y);
492  pts[3] = pt;
493 
494  pose.addPoints(pts);
495 
499  vpHomogeneousMatrix cMo_dementhon, cMo_lagrange;
500 
501  double residual_dementhon = std::numeric_limits<double>::max(),
502  residual_lagrange = std::numeric_limits<double>::max();
503  double residual_homography = pose.computeResidual(cMo_homography);
504  double residual_homography_ortho_iter = pose.computeResidual(cMo_homography_ortho_iter);
505 
506  if (pose.computePose(vpPose::DEMENTHON, cMo_dementhon)) {
507  residual_dementhon = pose.computeResidual(cMo_dementhon);
508  }
509 
510  if (pose.computePose(vpPose::LAGRANGE, cMo_lagrange)) {
511  residual_lagrange = pose.computeResidual(cMo_lagrange);
512  }
513 
514  std::vector<double> residuals;
515  residuals.push_back(residual_dementhon);
516  residuals.push_back(residual_lagrange);
517  residuals.push_back(residual_homography);
518  residuals.push_back(residual_homography_ortho_iter);
519  std::vector<vpHomogeneousMatrix> poses;
520  poses.push_back(cMo_dementhon);
521  poses.push_back(cMo_lagrange);
522  poses.push_back(cMo_homography);
523  poses.push_back(cMo_homography_ortho_iter);
524 
525  std::ptrdiff_t minIndex = std::min_element(residuals.begin(), residuals.end()) - residuals.begin();
526  cMo = *(poses.begin() + minIndex);
527  } else {
528  pose.computePose(m_mapOfCorrespondingPoseMethods[m_poseEstimationMethod], cMo);
529  }
530  }
531 
533  // Compute final pose using VVS
534  pose.computePose(vpPose::VIRTUAL_VS, cMo);
535  }
536 
537  // Only with HOMOGRAPHY_ORTHOGONAL_ITERATION we can directly get two solutions
539  if (cMo2) {
540  double scale = tagSize / 2.0;
541  double data_p0[] = {-scale, scale, 0};
542  double data_p1[] = {scale, scale, 0};
543  double data_p2[] = {scale, -scale, 0};
544  double data_p3[] = {-scale, -scale, 0};
545  matd_t *p[4] = {matd_create_data(3, 1, data_p0), matd_create_data(3, 1, data_p1),
546  matd_create_data(3, 1, data_p2), matd_create_data(3, 1, data_p3)};
547  matd_t *v[4];
548  for (int i = 0; i < 4; i++) {
549  double data_v[] = {(det->p[i][0] - cam.get_u0()) / cam.get_px(), (det->p[i][1] - cam.get_v0()) / cam.get_py(),
550  1};
551  v[i] = matd_create_data(3, 1, data_v);
552  }
553 
554  apriltag_pose_t solution1, solution2;
555  const int nIters = 50;
556  solution1.R = matd_create_data(3, 3, cMo.getRotationMatrix().data);
557  solution1.t = matd_create_data(3, 1, cMo.getTranslationVector().data);
558 
559  double err2;
560  get_second_solution(v, p, &solution1, &solution2, nIters, &err2);
561 
562  for (int i = 0; i < 4; i++) {
563  matd_destroy(p[i]);
564  matd_destroy(v[i]);
565  }
566 
567  if (solution2.R) {
568  convertHomogeneousMatrix(solution2, *cMo2);
569 
570  matd_destroy(solution2.R);
571  matd_destroy(solution2.t);
572  }
573 
574  matd_destroy(solution1.R);
575  matd_destroy(solution1.t);
576  }
577  }
578 
579  // Compute projection error with vpPose::computeResidual() for consistency
580  if (projErrors) {
581  *projErrors = pose.computeResidual(cMo);
582  }
583  if (projErrors2 && cMo2) {
584  *projErrors2 = pose.computeResidual(*cMo2);
585  }
586 
587  if (!m_zAlignedWithCameraFrame) {
589  // Apply a rotation of 180deg around x axis
590  oMo[0][0] = 1;
591  oMo[0][1] = 0;
592  oMo[0][2] = 0;
593  oMo[1][0] = 0;
594  oMo[1][1] = -1;
595  oMo[1][2] = 0;
596  oMo[2][0] = 0;
597  oMo[2][1] = 0;
598  oMo[2][2] = -1;
599  cMo = cMo * oMo;
600  if (cMo2) {
601  *cMo2 = *cMo2 * oMo;
602  }
603  }
604 
605  return true;
606  }
607 
608  void getPoseWithOrthogonalMethod(apriltag_detection_info_t &info, vpHomogeneousMatrix &cMo1,
609  vpHomogeneousMatrix *cMo2, double *err1, double *err2)
610  {
611  apriltag_pose_t pose1, pose2;
612  double err_1, err_2;
613  estimate_tag_pose_orthogonal_iteration(&info, &err_1, &pose1, &err_2, &pose2, 50);
614  if (err_1 <= err_2) {
615  convertHomogeneousMatrix(pose1, cMo1);
616  if (cMo2) {
617  if (pose2.R) {
618  convertHomogeneousMatrix(pose2, *cMo2);
619  } else {
620  *cMo2 = cMo1;
621  }
622  }
623  } else {
624  convertHomogeneousMatrix(pose2, cMo1);
625  if (cMo2) {
626  convertHomogeneousMatrix(pose1, *cMo2);
627  }
628  }
629 
630  matd_destroy(pose1.R);
631  matd_destroy(pose1.t);
632  if (pose2.R) {
633  matd_destroy(pose2.t);
634  }
635  matd_destroy(pose2.R);
636 
637  if (err1)
638  *err1 = err_1;
639  if (err2)
640  *err2 = err_2;
641  }
642 
643  bool getZAlignedWithCameraAxis() { return m_zAlignedWithCameraFrame; }
644 
645  bool getAprilTagDecodeSharpening(double &decodeSharpening) const
646  {
647  if (m_td) {
648  decodeSharpening = m_td->decode_sharpening;
649  return true;
650  }
651  return false;
652  }
653 
654  bool getNbThreads(int &nThreads) const
655  {
656  if (m_td) {
657  nThreads = m_td->nthreads;
658  return true;
659  }
660  return false;
661  }
662 
663  bool getQuadDecimate(float &quadDecimate) const
664  {
665  if (m_td) {
666  quadDecimate = m_td->quad_decimate;
667  return true;
668  }
669  return false;
670  }
671 
672  bool getQuadSigma(float &quadSigma) const
673  {
674  if (m_td) {
675  quadSigma = m_td->quad_sigma;
676  return true;
677  }
678  return false;
679  }
680 
681  bool getRefineEdges(bool &refineEdges) const
682  {
683  if (m_td) {
684  refineEdges = (m_td->refine_edges ? true : false);
685  return true;
686  }
687  return false;
688  }
689 
690  bool getZAlignedWithCameraAxis() const { return m_zAlignedWithCameraFrame; }
691 
692  std::vector<int> getTagsId() const { return m_tagsId; }
693 
694  void setAprilTagDecodeSharpening(double decodeSharpening)
695  {
696  if (m_td) {
697  m_td->decode_sharpening = decodeSharpening;
698  }
699  }
700 
701  void setNbThreads(int nThreads)
702  {
703  if (m_td) {
704  m_td->nthreads = nThreads;
705  }
706  }
707 
708  void setQuadDecimate(float quadDecimate)
709  {
710  if (m_td) {
711  m_td->quad_decimate = quadDecimate;
712  }
713  }
714 
715  void setQuadSigma(float quadSigma)
716  {
717  if (m_td) {
718  m_td->quad_sigma = quadSigma;
719  }
720  }
721 
722  void setRefineDecode(bool) {}
723 
724  void setRefineEdges(bool refineEdges)
725  {
726  if (m_td) {
727  m_td->refine_edges = refineEdges ? 1 : 0;
728  }
729  }
730 
731  void setRefinePose(bool) {}
732 
733  void setPoseEstimationMethod(const vpPoseEstimationMethod &method) { m_poseEstimationMethod = method; }
734 
735  void setZAlignedWithCameraAxis(bool zAlignedWithCameraFrame) { m_zAlignedWithCameraFrame = zAlignedWithCameraFrame; }
736 
737 protected:
738  std::map<vpPoseEstimationMethod, vpPose::vpPoseMethodType> m_mapOfCorrespondingPoseMethods;
740  std::vector<int> m_tagsId;
742  apriltag_detector_t *m_td;
743  apriltag_family_t *m_tf;
744  zarray_t *m_detections;
745  bool m_zAlignedWithCameraFrame;
746 };
747 #endif // DOXYGEN_SHOULD_SKIP_THIS
748 
750  const vpPoseEstimationMethod &poseEstimationMethod)
752  m_poseEstimationMethod(poseEstimationMethod), m_tagFamily(tagFamily), m_defaultCam(),
753  m_impl(new Impl(tagFamily, poseEstimationMethod))
754 {
755 }
756 
760  m_impl(new Impl(*o.m_impl))
761 {
762 }
763 
765 {
766  swap(*this, o);
767  return *this;
768 }
769 
771 
780 {
781  m_message.clear();
782  m_polygon.clear();
783  m_nb_objects = 0;
784 
785  std::vector<vpHomogeneousMatrix> cMo_vec;
786  const double tagSize = 1.0;
787  bool detected = m_impl->detect(I, tagSize, m_defaultCam, m_polygon, m_message, m_displayTag, m_displayTagColor,
788  m_displayTagThickness, NULL, NULL, NULL, NULL);
789  m_nb_objects = m_message.size();
790 
791  return detected;
792 }
793 
811 bool vpDetectorAprilTag::detect(const vpImage<unsigned char> &I, double tagSize, const vpCameraParameters &cam,
812  std::vector<vpHomogeneousMatrix> &cMo_vec, std::vector<vpHomogeneousMatrix> *cMo_vec2,
813  std::vector<double> *projErrors, std::vector<double> *projErrors2)
814 {
815  m_message.clear();
816  m_polygon.clear();
817  m_nb_objects = 0;
818 
819  cMo_vec.clear();
820  if (cMo_vec2) {
821  cMo_vec2->clear();
822  }
823  bool detected = m_impl->detect(I, tagSize, cam, m_polygon, m_message, m_displayTag, m_displayTagColor,
824  m_displayTagThickness, &cMo_vec, cMo_vec2, projErrors, projErrors2);
825  m_nb_objects = m_message.size();
826 
827  return detected;
828 }
829 
861 bool vpDetectorAprilTag::getPose(size_t tagIndex, double tagSize, const vpCameraParameters &cam,
862  vpHomogeneousMatrix &cMo, vpHomogeneousMatrix *cMo2, double *projError,
863  double *projError2)
864 {
865  return m_impl->getPose(tagIndex, tagSize, cam, cMo, cMo2, projError, projError2);
866 }
867 
885 std::vector<std::vector<vpPoint> > vpDetectorAprilTag::getTagsPoints3D(const std::vector<int> &tagsId,
886  const std::map<int, double> &tagsSize) const
887 {
888  std::vector<std::vector<vpPoint> > tagsPoints3D;
889 
890  double default_size = -1;
891  {
892  std::map<int, double>::const_iterator it = tagsSize.find(-1);
893  if (it != tagsSize.end()) {
894  default_size = it->second; // Default size
895  }
896  }
897  for (size_t i = 0; i < tagsId.size(); i++) {
898  std::map<int, double>::const_iterator it = tagsSize.find(tagsId[i]);
899  double tagSize = default_size; // Default size
900  if (it == tagsSize.end()) {
901  if (default_size < 0) { // no default size found
903  "Tag with id %d has no 3D size or there is no default 3D size defined", tagsId[i]));
904  }
905  } else {
906  tagSize = it->second;
907  }
908  std::vector<vpPoint> points3D(4);
909  if (m_impl->getZAlignedWithCameraAxis()) {
910  points3D[0] = vpPoint(-tagSize / 2, tagSize / 2, 0);
911  points3D[1] = vpPoint(tagSize / 2, tagSize / 2, 0);
912  points3D[2] = vpPoint(tagSize / 2, -tagSize / 2, 0);
913  points3D[3] = vpPoint(-tagSize / 2, -tagSize / 2, 0);
914  } else {
915  points3D[0] = vpPoint(-tagSize / 2, -tagSize / 2, 0);
916  points3D[1] = vpPoint(tagSize / 2, -tagSize / 2, 0);
917  points3D[2] = vpPoint(tagSize / 2, tagSize / 2, 0);
918  points3D[3] = vpPoint(-tagSize / 2, tagSize / 2, 0);
919  }
920  tagsPoints3D.push_back(points3D);
921  }
922 
923  return tagsPoints3D;
924 }
925 
931 std::vector<std::vector<vpImagePoint> > vpDetectorAprilTag::getTagsCorners() const { return m_polygon; }
932 
938 std::vector<int> vpDetectorAprilTag::getTagsId() const { return m_impl->getTagsId(); }
939 
941 {
942  return m_impl->setAprilTagDecodeSharpening(decodeSharpening);
943 }
944 
946 {
947  // back-up settings
948  double decodeSharpening = 0.25;
949  m_impl->getAprilTagDecodeSharpening(decodeSharpening);
950  int nThreads = 1;
951  m_impl->getNbThreads(nThreads);
952  float quadDecimate = 1;
953  m_impl->getQuadDecimate(quadDecimate);
954  float quadSigma = 0;
955  m_impl->getQuadSigma(quadSigma);
956  bool refineEdges = true;
957  m_impl->getRefineEdges(refineEdges);
958  bool zAxis = m_impl->getZAlignedWithCameraAxis();
959 
960  delete m_impl;
961  m_impl = new Impl(tagFamily, m_poseEstimationMethod);
962  m_impl->setAprilTagDecodeSharpening(decodeSharpening);
963  m_impl->setNbThreads(nThreads);
964  m_impl->setQuadDecimate(quadDecimate);
965  m_impl->setQuadSigma(quadSigma);
966  m_impl->setRefineEdges(refineEdges);
967  m_impl->setZAlignedWithCameraAxis(zAxis);
968 }
969 
976 {
977  if (nThreads > 0) {
978  m_impl->setNbThreads(nThreads);
979  }
980 }
981 
988 {
989  m_poseEstimationMethod = poseEstimationMethod;
990  m_impl->setPoseEstimationMethod(poseEstimationMethod);
991 }
992 
1005 void vpDetectorAprilTag::setAprilTagQuadDecimate(float quadDecimate) { m_impl->setQuadDecimate(quadDecimate); }
1006 
1019 void vpDetectorAprilTag::setAprilTagQuadSigma(float quadSigma) { m_impl->setQuadSigma(quadSigma); }
1020 
1021 #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS)
1022 
1025 vp_deprecated void vpDetectorAprilTag::setAprilTagRefineDecode(bool refineDecode)
1026 {
1027  m_impl->setRefineDecode(refineDecode);
1028 }
1029 #endif
1030 
1045 void vpDetectorAprilTag::setAprilTagRefineEdges(bool refineEdges) { m_impl->setRefineEdges(refineEdges); }
1046 
1047 #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS)
1048 
1051 vp_deprecated void vpDetectorAprilTag::setAprilTagRefinePose(bool refinePose) { m_impl->setRefinePose(refinePose); }
1052 #endif
1053 
1055 {
1056  using std::swap;
1057 
1058  swap(o1.m_impl, o2.m_impl);
1059 }
1060 
1066 void vpDetectorAprilTag::setZAlignedWithCameraAxis(bool zAlignedWithCameraFrame)
1067 {
1068  m_impl->setZAlignedWithCameraAxis(zAlignedWithCameraFrame);
1069 }
1070 
1071 #elif !defined(VISP_BUILD_SHARED_LIBS)
1072 // Work arround to avoid warning: libvisp_core.a(vpDetectorAprilTag.cpp.o) has
1073 // no symbols
1074 void dummy_vpDetectorAprilTag() {}
1075 #endif
AprilTag 16h5 pattern.
AprilTag Standard52h13 pattern.
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool(*func)(const vpHomogeneousMatrix &)=NULL)
Definition: vpPose.cpp:373
void setWorldCoordinates(double oX, double oY, double oZ)
Definition: vpPoint.cpp:113
void setAprilTagPoseEstimationMethod(const vpPoseEstimationMethod &poseEstimationMethod)
DEPRECATED AND WILL NOT DETECT ARTOOLKIT TAGS.
Implementation of an homogeneous matrix and operations on such kind of matrices.
AprilTag 36h11 pattern (recommended)
Type * bitmap
points toward the bitmap
Definition: vpImage.h:143
void setAprilTagQuadSigma(float quadSigma)
void set_uv(double u, double v)
Definition: vpImagePoint.h:357
Class to define RGB colors available for display functionnalities.
Definition: vpColor.h:157
AprilTag Circle21h7 pattern.
void addPoints(const std::vector< vpPoint > &lP)
Definition: vpPose.cpp:163
static const vpColor none
Definition: vpColor.h:229
error that can be emited by ViSP classes.
Definition: vpException.h:71
void setAprilTagDecodeSharpening(double decodeSharpening)
std::vector< std::vector< vpPoint > > getTagsPoints3D(const std::vector< int > &tagsId, const std::map< int, double > &tagsSize) const
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
Type * data
Address of the first element of the data array.
Definition: vpArray2D.h:145
bool getPose(size_t tagIndex, double tagSize, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, vpHomogeneousMatrix *cMo2=NULL, double *projError=NULL, double *projError2=NULL)
friend void swap(vpDetectorAprilTag &o1, vpDetectorAprilTag &o2)
static const vpColor green
Definition: vpColor.h:220
static const vpColor red
Definition: vpColor.h:217
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:81
void set_x(double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.cpp:511
AprilTag Circle49h12 pattern.
void set_y(double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.cpp:513
void setAprilTagQuadDecimate(float quadDecimate)
void setAprilTagFamily(const vpAprilTagFamily &tagFamily)
size_t m_nb_objects
Number of detected objects.
void setZAlignedWithCameraAxis(bool zAlignedWithCameraFrame)
void setAprilTagRefineDecode(bool refineDecode)
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition: vpPose.h:89
Generic class defining intrinsic camera parameters.
void setAprilTagNbThreads(int nThreads)
std::vector< std::vector< vpImagePoint > > getTagsCorners() const
std::vector< int > getTagsId() const
vpTranslationVector getTranslationVector() const
vpPoseEstimationMethod m_poseEstimationMethod
AprilTag Standard41h12 pattern.
unsigned int getHeight() const
Definition: vpImage.h:188
vpDetectorAprilTag & operator=(vpDetectorAprilTag o)
void setAprilTagRefineEdges(bool refineEdges)
std::vector< std::vector< vpImagePoint > > m_polygon
For each object, defines the polygon that contains the object.
vpDetectorAprilTag(const vpAprilTagFamily &tagFamily=TAG_36h11, const vpPoseEstimationMethod &poseEstimationMethod=HOMOGRAPHY_VIRTUAL_VS)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:88
AprilTag Custom48h12 pattern.
double computeResidual(const vpHomogeneousMatrix &cMo) const
Compute and return the sum of squared residuals expressed in meter^2 for the pose matrix cMo...
Definition: vpPose.cpp:335
static const vpColor yellow
Definition: vpColor.h:225
unsigned int m_displayTagThickness
unsigned int getWidth() const
Definition: vpImage.h:246
std::vector< std::string > m_message
Message attached to each object.
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
vpAprilTagFamily m_tagFamily
void setAprilTagRefinePose(bool refinePose)
vpRotationMatrix getRotationMatrix() const
AprilTag 25h9 pattern.
static const vpColor blue
Definition: vpColor.h:223
DEPRECATED AND POOR DETECTION PERFORMANCE.
bool detect(const vpImage< unsigned char > &I)