aruco.cpp
Go to the documentation of this file.
1 /*
2 By downloading, copying, installing or using the software you agree to this
3 license. If you do not agree to this license, do not download, install,
4 copy or use the software.
5 
6  License Agreement
7  For Open Source Computer Vision Library
8  (3-clause BSD License)
9 
10 Copyright (C) 2013, OpenCV Foundation, all rights reserved.
11 Third party copyrights are property of their respective owners.
12 
13 Redistribution and use in source and binary forms, with or without modification,
14 are permitted provided that the following conditions are met:
15 
16  * Redistributions of source code must retain the above copyright notice,
17  this list of conditions and the following disclaimer.
18 
19  * Redistributions in binary form must reproduce the above copyright notice,
20  this list of conditions and the following disclaimer in the documentation
21  and/or other materials provided with the distribution.
22 
23  * Neither the names of the copyright holders nor the names of the contributors
24  may be used to endorse or promote products derived from this software
25  without specific prior written permission.
26 
27 This software is provided by the copyright holders and contributors "as is" and
28 any express or implied warranties, including, but not limited to, the implied
29 warranties of merchantability and fitness for a particular purpose are
30 disclaimed. In no event shall copyright holders or contributors be liable for
31 any direct, indirect, incidental, special, exemplary, or consequential damages
32 (including, but not limited to, procurement of substitute goods or services;
33 loss of use, data, or profits; or business interruption) however caused
34 and on any theory of liability, whether in contract, strict liability,
35 or tort (including negligence or otherwise) arising in any way out of
36 the use of this software, even if advised of the possibility of such damage.
37 */
38 
39 #include "precomp.hpp"
40 #include "opencv2/aruco.hpp"
41 #include <opencv2/core.hpp>
42 #include <opencv2/imgproc.hpp>
43 
44 #include "apriltag_quad_thresh.hpp"
45 #include "zarray.hpp"
46 
47 //#define APRIL_DEBUG
48 #ifdef APRIL_DEBUG
49 #include "opencv2/imgcodecs.hpp"
50 #endif
51 
52 namespace cv {
53 namespace aruco {
54 
55 using namespace std;
56 
57 
62  : adaptiveThreshWinSizeMin(3),
63  adaptiveThreshWinSizeMax(23),
64  adaptiveThreshWinSizeStep(10),
65  adaptiveThreshConstant(7),
66  minMarkerPerimeterRate(0.03),
67  maxMarkerPerimeterRate(4.),
68  polygonalApproxAccuracyRate(0.03),
69  minCornerDistanceRate(0.05),
70  minDistanceToBorder(3),
71  minMarkerDistanceRate(0.05),
72  cornerRefinementMethod(CORNER_REFINE_NONE),
73  cornerRefinementWinSize(5),
74  cornerRefinementMaxIterations(30),
75  cornerRefinementMinAccuracy(0.1),
76  markerBorderBits(1),
77  perspectiveRemovePixelPerCell(4),
78  perspectiveRemoveIgnoredMarginPerCell(0.13),
79  maxErroneousBitsInBorderRate(0.35),
80  minOtsuStdDev(5.0),
81  errorCorrectionRate(0.6),
82  aprilTagQuadDecimate(0.0),
83  aprilTagQuadSigma(0.0),
84  aprilTagMinClusterPixels(5),
85  aprilTagMaxNmaxima(10),
86  aprilTagCriticalRad( (float)(10* CV_PI /180) ),
87  aprilTagMaxLineFitMse(10.0),
88  aprilTagMinWhiteBlackDiff(5),
89  aprilTagDeglitch(0),
90  detectInvertedMarker(false){}
91 
92 
96 Ptr<DetectorParameters> DetectorParameters::create() {
97  Ptr<DetectorParameters> params = makePtr<DetectorParameters>();
98  return params;
99 }
100 
101 
105 static void _convertToGrey(InputArray _in, OutputArray _out) {
106 
107  CV_Assert(_in.type() == CV_8UC1 || _in.type() == CV_8UC3);
108 
109  if(_in.type() == CV_8UC3)
110  cvtColor(_in, _out, COLOR_BGR2GRAY);
111  else
112  _in.copyTo(_out);
113 }
114 
115 
119 static void _threshold(InputArray _in, OutputArray _out, int winSize, double constant) {
120 
121  CV_Assert(winSize >= 3);
122  if(winSize % 2 == 0) winSize++; // win size must be odd
123  adaptiveThreshold(_in, _out, 255, ADAPTIVE_THRESH_MEAN_C, THRESH_BINARY_INV, winSize, constant);
124 }
125 
126 
131 static void _findMarkerContours(InputArray _in, vector< vector< Point2f > > &candidates,
132  vector< vector< Point > > &contoursOut, double minPerimeterRate,
133  double maxPerimeterRate, double accuracyRate,
135 
136  CV_Assert(minPerimeterRate > 0 && maxPerimeterRate > 0 && accuracyRate > 0 &&
137  minCornerDistanceRate >= 0 && minDistanceToBorder >= 0);
138 
139  // calculate maximum and minimum sizes in pixels
140  unsigned int minPerimeterPixels =
141  (unsigned int)(minPerimeterRate * max(_in.getMat().cols, _in.getMat().rows));
142  unsigned int maxPerimeterPixels =
143  (unsigned int)(maxPerimeterRate * max(_in.getMat().cols, _in.getMat().rows));
144 
145  Mat contoursImg;
146  _in.getMat().copyTo(contoursImg);
147  vector< vector< Point > > contours;
148  findContours(contoursImg, contours, RETR_LIST, CHAIN_APPROX_NONE);
149  // now filter list of contours
150  for(unsigned int i = 0; i < contours.size(); i++) {
151  // check perimeter
152  if(contours[i].size() < minPerimeterPixels || contours[i].size() > maxPerimeterPixels)
153  continue;
154 
155  // check is square and is convex
156  vector< Point > approxCurve;
157  approxPolyDP(contours[i], approxCurve, double(contours[i].size()) * accuracyRate, true);
158  if(approxCurve.size() != 4 || !isContourConvex(approxCurve)) continue;
159 
160  // check min distance between corners
161  double minDistSq =
162  max(contoursImg.cols, contoursImg.rows) * max(contoursImg.cols, contoursImg.rows);
163  for(int j = 0; j < 4; j++) {
164  double d = (double)(approxCurve[j].x - approxCurve[(j + 1) % 4].x) *
165  (double)(approxCurve[j].x - approxCurve[(j + 1) % 4].x) +
166  (double)(approxCurve[j].y - approxCurve[(j + 1) % 4].y) *
167  (double)(approxCurve[j].y - approxCurve[(j + 1) % 4].y);
168  minDistSq = min(minDistSq, d);
169  }
170  double minCornerDistancePixels = double(contours[i].size()) * minCornerDistanceRate;
171  if(minDistSq < minCornerDistancePixels * minCornerDistancePixels) continue;
172 
173  // check if it is too near to the image border
174  bool tooNearBorder = false;
175  for(int j = 0; j < 4; j++) {
176  if(approxCurve[j].x < minDistanceToBorder || approxCurve[j].y < minDistanceToBorder ||
177  approxCurve[j].x > contoursImg.cols - 1 - minDistanceToBorder ||
178  approxCurve[j].y > contoursImg.rows - 1 - minDistanceToBorder)
179  tooNearBorder = true;
180  }
181  if(tooNearBorder) continue;
182 
183  // if it passes all the test, add to candidates vector
184  vector< Point2f > currentCandidate;
185  currentCandidate.resize(4);
186  for(int j = 0; j < 4; j++) {
187  currentCandidate[j] = Point2f((float)approxCurve[j].x, (float)approxCurve[j].y);
188  }
189  candidates.push_back(currentCandidate);
190  contoursOut.push_back(contours[i]);
191  }
192 }
193 
194 
198 static void _reorderCandidatesCorners(vector< vector< Point2f > > &candidates) {
199 
200  for(unsigned int i = 0; i < candidates.size(); i++) {
201  double dx1 = candidates[i][1].x - candidates[i][0].x;
202  double dy1 = candidates[i][1].y - candidates[i][0].y;
203  double dx2 = candidates[i][2].x - candidates[i][0].x;
204  double dy2 = candidates[i][2].y - candidates[i][0].y;
205  double crossProduct = (dx1 * dy2) - (dy1 * dx2);
206 
207  if(crossProduct < 0.0) { // not clockwise direction
208  swap(candidates[i][1], candidates[i][3]);
209  }
210  }
211 }
212 
213 
217 static void _filterTooCloseCandidates(const vector< vector< Point2f > > &candidatesIn,
218  vector< vector< Point2f > > &candidatesOut,
219  const vector< vector< Point > > &contoursIn,
220  vector< vector< Point > > &contoursOut,
221  double minMarkerDistanceRate) {
222 
223  CV_Assert(minMarkerDistanceRate >= 0);
224 
225  vector< pair< int, int > > nearCandidates;
226  for(unsigned int i = 0; i < candidatesIn.size(); i++) {
227  for(unsigned int j = i + 1; j < candidatesIn.size(); j++) {
228 
229  int minimumPerimeter = min((int)contoursIn[i].size(), (int)contoursIn[j].size() );
230 
231  // fc is the first corner considered on one of the markers, 4 combinations are possible
232  for(int fc = 0; fc < 4; fc++) {
233  double distSq = 0;
234  for(int c = 0; c < 4; c++) {
235  // modC is the corner considering first corner is fc
236  int modC = (c + fc) % 4;
237  distSq += (candidatesIn[i][modC].x - candidatesIn[j][c].x) *
238  (candidatesIn[i][modC].x - candidatesIn[j][c].x) +
239  (candidatesIn[i][modC].y - candidatesIn[j][c].y) *
240  (candidatesIn[i][modC].y - candidatesIn[j][c].y);
241  }
242  distSq /= 4.;
243 
244  // if mean square distance is too low, remove the smaller one of the two markers
245  double minMarkerDistancePixels = double(minimumPerimeter) * minMarkerDistanceRate;
246  if(distSq < minMarkerDistancePixels * minMarkerDistancePixels) {
247  nearCandidates.push_back(pair< int, int >(i, j));
248  break;
249  }
250  }
251  }
252  }
253 
254  // mark smaller one in pairs to remove
255  vector< bool > toRemove(candidatesIn.size(), false);
256  for(unsigned int i = 0; i < nearCandidates.size(); i++) {
257  // if one of the marker has been already markerd to removed, dont need to do anything
258  if(toRemove[nearCandidates[i].first] || toRemove[nearCandidates[i].second]) continue;
259  size_t perimeter1 = contoursIn[nearCandidates[i].first].size();
260  size_t perimeter2 = contoursIn[nearCandidates[i].second].size();
261  if(perimeter1 > perimeter2)
262  toRemove[nearCandidates[i].second] = true;
263  else
264  toRemove[nearCandidates[i].first] = true;
265  }
266 
267  // remove extra candidates
268  candidatesOut.clear();
269  unsigned long totalRemaining = 0;
270  for(unsigned int i = 0; i < toRemove.size(); i++)
271  if(!toRemove[i]) totalRemaining++;
272  candidatesOut.resize(totalRemaining);
273  contoursOut.resize(totalRemaining);
274  for(unsigned int i = 0, currIdx = 0; i < candidatesIn.size(); i++) {
275  if(toRemove[i]) continue;
276  candidatesOut[currIdx] = candidatesIn[i];
277  contoursOut[currIdx] = contoursIn[i];
278  currIdx++;
279  }
280 }
281 
282 
287 class DetectInitialCandidatesParallel : public ParallelLoopBody {
288  public:
290  vector< vector< vector< Point2f > > > *_candidatesArrays,
291  vector< vector< vector< Point > > > *_contoursArrays,
292  const Ptr<DetectorParameters> &_params)
293  : grey(_grey), candidatesArrays(_candidatesArrays), contoursArrays(_contoursArrays),
294  params(_params) {}
295 
296  void operator()(const Range &range) const CV_OVERRIDE {
297  const int begin = range.start;
298  const int end = range.end;
299 
300  for(int i = begin; i < end; i++) {
301  int currScale =
302  params->adaptiveThreshWinSizeMin + i * params->adaptiveThreshWinSizeStep;
303  // threshold
304  Mat thresh;
305  _threshold(*grey, thresh, currScale, params->adaptiveThreshConstant);
306 
307  // detect rectangles
308  _findMarkerContours(thresh, (*candidatesArrays)[i], (*contoursArrays)[i],
309  params->minMarkerPerimeterRate, params->maxMarkerPerimeterRate,
310  params->polygonalApproxAccuracyRate, params->minCornerDistanceRate,
311  params->minDistanceToBorder);
312  }
313  }
314 
315  private:
317 
318  const Mat *grey;
319  vector< vector< vector< Point2f > > > *candidatesArrays;
320  vector< vector< vector< Point > > > *contoursArrays;
321  const Ptr<DetectorParameters> &params;
322 };
323 
324 
328 static void _detectInitialCandidates(const Mat &grey, vector< vector< Point2f > > &candidates,
329  vector< vector< Point > > &contours,
330  const Ptr<DetectorParameters> &params) {
331 
332  CV_Assert(params->adaptiveThreshWinSizeMin >= 3 && params->adaptiveThreshWinSizeMax >= 3);
333  CV_Assert(params->adaptiveThreshWinSizeMax >= params->adaptiveThreshWinSizeMin);
334  CV_Assert(params->adaptiveThreshWinSizeStep > 0);
335 
336  // number of window sizes (scales) to apply adaptive thresholding
337  int nScales = (params->adaptiveThreshWinSizeMax - params->adaptiveThreshWinSizeMin) /
338  params->adaptiveThreshWinSizeStep + 1;
339 
340  vector< vector< vector< Point2f > > > candidatesArrays((size_t) nScales);
341  vector< vector< vector< Point > > > contoursArrays((size_t) nScales);
342 
344  // for(int i = 0; i < nScales; i++) {
345  // int currScale = params.adaptiveThreshWinSizeMin + i*params.adaptiveThreshWinSizeStep;
346  // // treshold
347  // Mat thresh;
348  // _threshold(grey, thresh, currScale, params.adaptiveThreshConstant);
349  // // detect rectangles
350  // _findMarkerContours(thresh, candidatesArrays[i], contoursArrays[i],
351  // params.minMarkerPerimeterRate,
352  // params.maxMarkerPerimeterRate, params.polygonalApproxAccuracyRate,
353  // params.minCornerDistance, params.minDistanceToBorder);
354  //}
355 
356  // this is the parallel call for the previous commented loop (result is equivalent)
357  parallel_for_(Range(0, nScales), DetectInitialCandidatesParallel(&grey, &candidatesArrays,
358  &contoursArrays, params));
359 
360  // join candidates
361  for(int i = 0; i < nScales; i++) {
362  for(unsigned int j = 0; j < candidatesArrays[i].size(); j++) {
363  candidates.push_back(candidatesArrays[i][j]);
364  contours.push_back(contoursArrays[i][j]);
365  }
366  }
367 }
368 
369 
373 static void _detectCandidates(InputArray _image, vector< vector< Point2f > >& candidatesOut,
374  vector< vector< Point > >& contoursOut, const Ptr<DetectorParameters> &_params) {
375 
376  Mat image = _image.getMat();
377  CV_Assert(image.total() != 0);
378 
380  Mat grey;
381  _convertToGrey(image, grey);
382 
383  vector< vector< Point2f > > candidates;
384  vector< vector< Point > > contours;
386  _detectInitialCandidates(grey, candidates, contours, _params);
387 
389  _reorderCandidatesCorners(candidates);
390 
392  _filterTooCloseCandidates(candidates, candidatesOut, contours, contoursOut,
393  _params->minMarkerDistanceRate);
394 }
395 
396 
401 static Mat _extractBits(InputArray _image, InputArray _corners, int markerSize,
402  int markerBorderBits, int cellSize, double cellMarginRate,
403  double minStdDevOtsu) {
404 
405  CV_Assert(_image.getMat().channels() == 1);
406  CV_Assert(_corners.total() == 4);
407  CV_Assert(markerBorderBits > 0 && cellSize > 0 && cellMarginRate >= 0 && cellMarginRate <= 1);
408  CV_Assert(minStdDevOtsu >= 0);
409 
410  // number of bits in the marker
411  int markerSizeWithBorders = markerSize + 2 * markerBorderBits;
412  int cellMarginPixels = int(cellMarginRate * cellSize);
413 
414  Mat resultImg; // marker image after removing perspective
415  int resultImgSize = markerSizeWithBorders * cellSize;
416  Mat resultImgCorners(4, 1, CV_32FC2);
417  resultImgCorners.ptr< Point2f >(0)[0] = Point2f(0, 0);
418  resultImgCorners.ptr< Point2f >(0)[1] = Point2f((float)resultImgSize - 1, 0);
419  resultImgCorners.ptr< Point2f >(0)[2] =
420  Point2f((float)resultImgSize - 1, (float)resultImgSize - 1);
421  resultImgCorners.ptr< Point2f >(0)[3] = Point2f(0, (float)resultImgSize - 1);
422 
423  // remove perspective
424  Mat transformation = getPerspectiveTransform(_corners, resultImgCorners);
425  warpPerspective(_image, resultImg, transformation, Size(resultImgSize, resultImgSize),
426  INTER_NEAREST);
427 
428  // output image containing the bits
429  Mat bits(markerSizeWithBorders, markerSizeWithBorders, CV_8UC1, Scalar::all(0));
430 
431  // check if standard deviation is enough to apply Otsu
432  // if not enough, it probably means all bits are the same color (black or white)
433  Mat mean, stddev;
434  // Remove some border just to avoid border noise from perspective transformation
435  Mat innerRegion = resultImg.colRange(cellSize / 2, resultImg.cols - cellSize / 2)
436  .rowRange(cellSize / 2, resultImg.rows - cellSize / 2);
437  meanStdDev(innerRegion, mean, stddev);
438  if(stddev.ptr< double >(0)[0] < minStdDevOtsu) {
439  // all black or all white, depending on mean value
440  if(mean.ptr< double >(0)[0] > 127)
441  bits.setTo(1);
442  else
443  bits.setTo(0);
444  return bits;
445  }
446 
447  // now extract code, first threshold using Otsu
448  threshold(resultImg, resultImg, 125, 255, THRESH_BINARY | THRESH_OTSU);
449 
450  // for each cell
451  for(int y = 0; y < markerSizeWithBorders; y++) {
452  for(int x = 0; x < markerSizeWithBorders; x++) {
453  int Xstart = x * (cellSize) + cellMarginPixels;
454  int Ystart = y * (cellSize) + cellMarginPixels;
455  Mat square = resultImg(Rect(Xstart, Ystart, cellSize - 2 * cellMarginPixels,
456  cellSize - 2 * cellMarginPixels));
457  // count white pixels on each cell to assign its value
458  size_t nZ = (size_t) countNonZero(square);
459  if(nZ > square.total() / 2) bits.at< unsigned char >(y, x) = 1;
460  }
461  }
462 
463  return bits;
464 }
465 
466 
467 
471 static int _getBorderErrors(const Mat &bits, int markerSize, int borderSize) {
472 
473  int sizeWithBorders = markerSize + 2 * borderSize;
474 
475  CV_Assert(markerSize > 0 && bits.cols == sizeWithBorders && bits.rows == sizeWithBorders);
476 
477  int totalErrors = 0;
478  for(int y = 0; y < sizeWithBorders; y++) {
479  for(int k = 0; k < borderSize; k++) {
480  if(bits.ptr< unsigned char >(y)[k] != 0) totalErrors++;
481  if(bits.ptr< unsigned char >(y)[sizeWithBorders - 1 - k] != 0) totalErrors++;
482  }
483  }
484  for(int x = borderSize; x < sizeWithBorders - borderSize; x++) {
485  for(int k = 0; k < borderSize; k++) {
486  if(bits.ptr< unsigned char >(k)[x] != 0) totalErrors++;
487  if(bits.ptr< unsigned char >(sizeWithBorders - 1 - k)[x] != 0) totalErrors++;
488  }
489  }
490  return totalErrors;
491 }
492 
493 
497 static bool _identifyOneCandidate(const Ptr<Dictionary>& dictionary, InputArray _image,
498  vector<Point2f>& _corners, int& idx,
499  const Ptr<DetectorParameters>& params)
500 {
501  CV_Assert(_corners.size() == 4);
502  CV_Assert(_image.getMat().total() != 0);
503  CV_Assert(params->markerBorderBits > 0);
504 
505  // get bits
506  Mat candidateBits =
507  _extractBits(_image, _corners, dictionary->markerSize, params->markerBorderBits,
508  params->perspectiveRemovePixelPerCell,
509  params->perspectiveRemoveIgnoredMarginPerCell, params->minOtsuStdDev);
510 
511  // analyze border bits
512  int maximumErrorsInBorder =
513  int(dictionary->markerSize * dictionary->markerSize * params->maxErroneousBitsInBorderRate);
514  int borderErrors =
515  _getBorderErrors(candidateBits, dictionary->markerSize, params->markerBorderBits);
516 
517  // check if it is a white marker
518  if(params->detectInvertedMarker){
519  // to get from 255 to 1
520  Mat invertedImg = ~candidateBits-254;
521  int invBError = _getBorderErrors(invertedImg, dictionary->markerSize, params->markerBorderBits);
522  // white marker
523  if(invBError<borderErrors){
524  borderErrors = invBError;
525  invertedImg.copyTo(candidateBits);
526  }
527  }
528  if(borderErrors > maximumErrorsInBorder) return false;
529 
530  // take only inner bits
531  Mat onlyBits =
532  candidateBits.rowRange(params->markerBorderBits,
533  candidateBits.rows - params->markerBorderBits)
534  .colRange(params->markerBorderBits, candidateBits.rows - params->markerBorderBits);
535 
536  // try to indentify the marker
537  int rotation;
538  if(!dictionary->identify(onlyBits, idx, rotation, params->errorCorrectionRate))
539  return false;
540 
541  // shift corner positions to the correct rotation
542  if(rotation != 0) {
543  std::rotate(_corners.begin(), _corners.begin() + 4 - rotation, _corners.end());
544  }
545  return true;
546 }
547 
548 
553 class IdentifyCandidatesParallel : public ParallelLoopBody {
554  public:
555  IdentifyCandidatesParallel(const Mat& _grey, vector< vector< Point2f > >& _candidates,
556  const Ptr<Dictionary> &_dictionary,
557  vector< int >& _idsTmp, vector< char >& _validCandidates,
558  const Ptr<DetectorParameters> &_params)
559  : grey(_grey), candidates(_candidates), dictionary(_dictionary),
560  idsTmp(_idsTmp), validCandidates(_validCandidates), params(_params) {}
561 
562  void operator()(const Range &range) const CV_OVERRIDE {
563  const int begin = range.start;
564  const int end = range.end;
565 
566  for(int i = begin; i < end; i++) {
567  int currId;
568  if(_identifyOneCandidate(dictionary, grey, candidates[i], currId, params)) {
569  validCandidates[i] = 1;
570  idsTmp[i] = currId;
571  }
572  }
573  }
574 
575  private:
576  IdentifyCandidatesParallel &operator=(const IdentifyCandidatesParallel &); // to quiet MSVC
577 
578  const Mat &grey;
579  vector< vector< Point2f > >& candidates;
580  const Ptr<Dictionary> &dictionary;
581  vector< int > &idsTmp;
582  vector< char > &validCandidates;
583  const Ptr<DetectorParameters> &params;
584 };
585 
586 
587 
591 static void _copyVector2Output(vector< vector< Point2f > > &vec, OutputArrayOfArrays out) {
592  out.create((int)vec.size(), 1, CV_32FC2);
593 
594  if(out.isMatVector()) {
595  for (unsigned int i = 0; i < vec.size(); i++) {
596  out.create(4, 1, CV_32FC2, i);
597  Mat &m = out.getMatRef(i);
598  Mat(Mat(vec[i]).t()).copyTo(m);
599  }
600  }
601  else if(out.isUMatVector()) {
602  for (unsigned int i = 0; i < vec.size(); i++) {
603  out.create(4, 1, CV_32FC2, i);
604  UMat &m = out.getUMatRef(i);
605  Mat(Mat(vec[i]).t()).copyTo(m);
606  }
607  }
608  else if(out.kind() == _OutputArray::STD_VECTOR_VECTOR){
609  for (unsigned int i = 0; i < vec.size(); i++) {
610  out.create(4, 1, CV_32FC2, i);
611  Mat m = out.getMat(i);
612  Mat(Mat(vec[i]).t()).copyTo(m);
613  }
614  }
615  else {
616  CV_Error(cv::Error::StsNotImplemented,
617  "Only Mat vector, UMat vector, and vector<vector> OutputArrays are currently supported.");
618  }
619 }
620 
621 
622 
626 static void _identifyCandidates(InputArray _image, vector< vector< Point2f > >& _candidates,
627  vector< vector<Point> >& _contours, const Ptr<Dictionary> &_dictionary,
628  vector< vector< Point2f > >& _accepted, vector< int >& ids,
629  const Ptr<DetectorParameters> &params,
630  OutputArrayOfArrays _rejected = noArray()) {
631 
632  int ncandidates = (int)_candidates.size();
633 
634  vector< vector< Point2f > > accepted;
635  vector< vector< Point2f > > rejected;
636 
637  vector< vector< Point > > contours;
638 
639  CV_Assert(_image.getMat().total() != 0);
640 
641  Mat grey;
642  _convertToGrey(_image.getMat(), grey);
643 
644  vector< int > idsTmp(ncandidates, -1);
645  vector< char > validCandidates(ncandidates, 0);
646 
648  // for (int i = 0; i < ncandidates; i++) {
649  // int currId = i;
650  // Mat currentCandidate = _candidates.getMat(i);
651  // if (_identifyOneCandidate(dictionary, grey, currentCandidate, currId, params)) {
652  // validCandidates[i] = 1;
653  // idsTmp[i] = currId;
654  // }
655  //}
656 
657  // this is the parallel call for the previous commented loop (result is equivalent)
658  parallel_for_(Range(0, ncandidates),
659  IdentifyCandidatesParallel(grey, _candidates, _dictionary, idsTmp,
660  validCandidates, params));
661 
662  for(int i = 0; i < ncandidates; i++) {
663  if(validCandidates[i] == 1) {
664  accepted.push_back(_candidates[i]);
665  ids.push_back(idsTmp[i]);
666 
667  contours.push_back(_contours[i]);
668 
669  } else {
670  rejected.push_back(_candidates[i]);
671  }
672  }
673 
674  // parse output
675  _accepted = accepted;
676 
677  _contours= contours;
678 
679  if(_rejected.needed()) {
680  _copyVector2Output(rejected, _rejected);
681  }
682 }
683 
684 
688 static void _filterDetectedMarkers(vector< vector< Point2f > >& _corners, vector< int >& _ids, vector< vector< Point> >& _contours) {
689 
690  CV_Assert(_corners.size() == _ids.size());
691  if(_corners.empty()) return;
692 
693  // mark markers that will be removed
694  vector< bool > toRemove(_corners.size(), false);
695  bool atLeastOneRemove = false;
696 
697  // remove repeated markers with same id, if one contains the other (doble border bug)
698  for(unsigned int i = 0; i < _corners.size() - 1; i++) {
699  for(unsigned int j = i + 1; j < _corners.size(); j++) {
700  if(_ids[i] != _ids[j]) continue;
701 
702  // check if first marker is inside second
703  bool inside = true;
704  for(unsigned int p = 0; p < 4; p++) {
705  Point2f point = _corners[j][p];
706  if(pointPolygonTest(_corners[i], point, false) < 0) {
707  inside = false;
708  break;
709  }
710  }
711  if(inside) {
712  toRemove[j] = true;
713  atLeastOneRemove = true;
714  continue;
715  }
716 
717  // check the second marker
718  inside = true;
719  for(unsigned int p = 0; p < 4; p++) {
720  Point2f point = _corners[i][p];
721  if(pointPolygonTest(_corners[j], point, false) < 0) {
722  inside = false;
723  break;
724  }
725  }
726  if(inside) {
727  toRemove[i] = true;
728  atLeastOneRemove = true;
729  continue;
730  }
731  }
732  }
733 
734  // parse output
735  if(atLeastOneRemove) {
736  vector< vector< Point2f > >::iterator filteredCorners = _corners.begin();
737  vector< int >::iterator filteredIds = _ids.begin();
738 
739  vector< vector< Point > >::iterator filteredContours = _contours.begin();
740 
741  for(unsigned int i = 0; i < toRemove.size(); i++) {
742  if(!toRemove[i]) {
743  *filteredCorners++ = _corners[i];
744  *filteredIds++ = _ids[i];
745 
746  *filteredContours++ = _contours[i];
747  }
748  }
749 
750  _ids.erase(filteredIds, _ids.end());
751  _corners.erase(filteredCorners, _corners.end());
752 
753  _contours.erase(filteredContours, _contours.end());
754  }
755 }
756 
757 
758 
762 static void _getSingleMarkerObjectPoints(float markerLength, OutputArray _objPoints) {
763 
764  CV_Assert(markerLength > 0);
765 
766  _objPoints.create(4, 1, CV_32FC3);
767  Mat objPoints = _objPoints.getMat();
768  // set coordinate system in the middle of the marker, with Z pointing out
769  objPoints.ptr< Vec3f >(0)[0] = Vec3f(-markerLength / 2.f, markerLength / 2.f, 0);
770  objPoints.ptr< Vec3f >(0)[1] = Vec3f(markerLength / 2.f, markerLength / 2.f, 0);
771  objPoints.ptr< Vec3f >(0)[2] = Vec3f(markerLength / 2.f, -markerLength / 2.f, 0);
772  objPoints.ptr< Vec3f >(0)[3] = Vec3f(-markerLength / 2.f, -markerLength / 2.f, 0);
773 }
774 
775 
776 
777 
782 class MarkerSubpixelParallel : public ParallelLoopBody {
783  public:
784  MarkerSubpixelParallel(const Mat *_grey, OutputArrayOfArrays _corners,
785  const Ptr<DetectorParameters> &_params)
786  : grey(_grey), corners(_corners), params(_params) {}
787 
788  void operator()(const Range &range) const CV_OVERRIDE {
789  const int begin = range.start;
790  const int end = range.end;
791 
792  for(int i = begin; i < end; i++) {
793  cornerSubPix(*grey, corners.getMat(i),
794  Size(params->cornerRefinementWinSize, params->cornerRefinementWinSize),
795  Size(-1, -1), TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
796  params->cornerRefinementMaxIterations,
797  params->cornerRefinementMinAccuracy));
798  }
799  }
800 
801  private:
802  MarkerSubpixelParallel &operator=(const MarkerSubpixelParallel &); // to quiet MSVC
803 
804  const Mat *grey;
805  OutputArrayOfArrays corners;
806  const Ptr<DetectorParameters> &params;
807 };
808 
813 static Point3f _interpolate2Dline(const std::vector<cv::Point2f>& nContours){
814  float minX, minY, maxX, maxY;
815  minX = maxX = nContours[0].x;
816  minY = maxY = nContours[0].y;
817 
818  for(unsigned int i = 0; i< nContours.size(); i++){
819  minX = nContours[i].x < minX ? nContours[i].x : minX;
820  minY = nContours[i].y < minY ? nContours[i].y : minY;
821  maxX = nContours[i].x > maxX ? nContours[i].x : maxX;
822  maxY = nContours[i].y > maxY ? nContours[i].y : maxY;
823  }
824 
825  Mat A = Mat::ones((int)nContours.size(), 2, CV_32F); // Coefficient Matrix (N x 2)
826  Mat B((int)nContours.size(), 1, CV_32F); // Variables Matrix (N x 1)
827  Mat C; // Constant
828 
829  if(maxX - minX > maxY - minY){
830  for(unsigned int i =0; i < nContours.size(); i++){
831  A.at<float>(i,0)= nContours[i].x;
832  B.at<float>(i,0)= nContours[i].y;
833  }
834 
835  solve(A, B, C, DECOMP_NORMAL);
836 
837  return Point3f(C.at<float>(0, 0), -1., C.at<float>(1, 0));
838  }
839  else{
840  for(unsigned int i =0; i < nContours.size(); i++){
841  A.at<float>(i,0)= nContours[i].y;
842  B.at<float>(i,0)= nContours[i].x;
843  }
844 
845  solve(A, B, C, DECOMP_NORMAL);
846 
847  return Point3f(-1., C.at<float>(0, 0), C.at<float>(1, 0));
848  }
849 
850 }
851 
858 static Point2f _getCrossPoint(Point3f nLine1, Point3f nLine2){
859  Matx22f A(nLine1.x, nLine1.y, nLine2.x, nLine2.y);
860  Vec2f B(-nLine1.z, -nLine2.z);
861  return Vec2f(A.solve(B).val);
862 }
863 
864 static void _distortPoints(vector<cv::Point2f>& in, const Mat& camMatrix, const Mat& distCoeff) {
865  // trivial extrinsics
866  Matx31f Rvec(0,0,0);
867  Matx31f Tvec(0,0,0);
868 
869  // calculate 3d points and then reproject, so opencv makes the distortion internally
870  vector<cv::Point3f> cornersPoints3d;
871  for (unsigned int i = 0; i < in.size(); i++){
872  float x= (in[i].x - float(camMatrix.at<double>(0, 2))) / float(camMatrix.at<double>(0, 0));
873  float y= (in[i].y - float(camMatrix.at<double>(1, 2))) / float(camMatrix.at<double>(1, 1));
874  cornersPoints3d.push_back(Point3f(x,y,1));
875  }
876  cv::projectPoints(cornersPoints3d, Rvec, Tvec, camMatrix, distCoeff, in);
877 }
878 
886 static void _refineCandidateLines(std::vector<Point>& nContours, std::vector<Point2f>& nCorners, const Mat& camMatrix, const Mat& distCoeff){
887  vector<Point2f> contour2f(nContours.begin(), nContours.end());
888 
889  if(!camMatrix.empty() && !distCoeff.empty()){
890  undistortPoints(contour2f, contour2f, camMatrix, distCoeff);
891  }
892 
893  /* 5 groups :: to group the edges
894  * 4 - classified by its corner
895  * extra group - (temporary) if contours do not begin with a corner
896  */
897  vector<Point2f> cntPts[5];
898  int cornerIndex[4]={-1};
899  int group=4;
900 
901  for ( unsigned int i =0; i < nContours.size(); i++ ) {
902  for(unsigned int j=0; j<4; j++){
903  if ( nCorners[j] == contour2f[i] ){
904  cornerIndex[j] = i;
905  group=j;
906  }
907  }
908  cntPts[group].push_back(contour2f[i]);
909  }
910 
911  // saves extra group into corresponding
912  if( !cntPts[4].empty() ){
913  for( unsigned int i=0; i < cntPts[4].size() ; i++ )
914  cntPts[group].push_back(cntPts[4].at(i));
915  cntPts[4].clear();
916  }
917 
918  //Evaluate contour direction :: using the position of the detected corners
919  int inc=1;
920 
921  inc = ( (cornerIndex[0] > cornerIndex[1]) && (cornerIndex[3] > cornerIndex[0]) ) ? -1:inc;
922  inc = ( (cornerIndex[2] > cornerIndex[3]) && (cornerIndex[1] > cornerIndex[2]) ) ? -1:inc;
923 
924  // calculate the line :: who passes through the grouped points
925  Point3f lines[4];
926  for(int i=0; i<4; i++){
927  // Don't try to "interpolate" single points
928  if (cntPts[i].size() < 2) return;
929  lines[i]=_interpolate2Dline(cntPts[i]);
930  }
931 
932  /*
933  * calculate the corner :: where the lines crosses to each other
934  * clockwise direction no clockwise direction
935  * 0 1
936  * .---. 1 .---. 2
937  * | | | |
938  * 3 .___. 0 .___.
939  * 2 3
940  */
941  for(int i=0; i < 4; i++){
942  if(inc<0)
943  nCorners[i] = _getCrossPoint(lines[ i ], lines[ (i+1)%4 ]); // 01 12 23 30
944  else
945  nCorners[i] = _getCrossPoint(lines[ i ], lines[ (i+3)%4 ]); // 30 01 12 23
946  }
947 
948  if(!camMatrix.empty() && !distCoeff.empty()){
949  _distortPoints(nCorners, camMatrix, distCoeff);
950  }
951 }
952 
953 
958 class MarkerContourParallel : public ParallelLoopBody {
959  public:
960  MarkerContourParallel( vector< vector< Point > >& _contours, vector< vector< Point2f > >& _candidates, const Mat& _camMatrix, const Mat& _distCoeff)
961  : contours(_contours), candidates(_candidates), camMatrix(_camMatrix), distCoeff(_distCoeff){}
962 
963  void operator()(const Range &range) const CV_OVERRIDE {
964 
965  for(int i = range.start; i < range.end; i++) {
966  _refineCandidateLines(contours[i], candidates[i], camMatrix, distCoeff);
967  }
968  }
969 
970  private:
972  return *this;
973  }
974 
975  vector< vector< Point > >& contours;
976  vector< vector< Point2f > >& candidates;
977  const Mat& camMatrix;
978  const Mat& distCoeff;
979 };
980 
981 #ifdef APRIL_DEBUG
982 static void _darken(const Mat &im){
983  for (int y = 0; y < im.rows; y++) {
984  for (int x = 0; x < im.cols; x++) {
985  im.data[im.cols*y+x] /= 2;
986  }
987  }
988 }
989 #endif
990 
998 static void _apriltag(Mat im_orig, const Ptr<DetectorParameters> & _params, std::vector< std::vector< Point2f > > &candidates,
999  std::vector< std::vector< Point > > &contours){
1000 
1004  Mat quad_im;
1005  im_orig.copyTo(quad_im);
1006 
1007  if (_params->aprilTagQuadDecimate > 1){
1008  resize(im_orig, quad_im, Size(), 1/_params->aprilTagQuadDecimate, 1/_params->aprilTagQuadDecimate, INTER_AREA );
1009  }
1010 
1011  // Apply a Blur
1012  if (_params->aprilTagQuadSigma != 0) {
1013  // compute a reasonable kernel width by figuring that the
1014  // kernel should go out 2 std devs.
1015  //
1016  // max sigma ksz
1017  // 0.499 1 (disabled)
1018  // 0.999 3
1019  // 1.499 5
1020  // 1.999 7
1021 
1022  float sigma = fabsf((float) _params->aprilTagQuadSigma);
1023 
1024  int ksz = cvFloor(4 * sigma); // 2 std devs in each direction
1025  ksz |= 1; // make odd number
1026 
1027  if (ksz > 1) {
1028  if (_params->aprilTagQuadSigma > 0)
1029  GaussianBlur(quad_im, quad_im, Size(ksz, ksz), sigma, sigma, BORDER_REPLICATE);
1030  else {
1031  Mat orig;
1032  quad_im.copyTo(orig);
1033  GaussianBlur(quad_im, quad_im, Size(ksz, ksz), sigma, sigma, BORDER_REPLICATE);
1034 
1035  // SHARPEN the image by subtracting the low frequency components.
1036  for (int y = 0; y < orig.rows; y++) {
1037  for (int x = 0; x < orig.cols; x++) {
1038  int vorig = orig.data[y*orig.step + x];
1039  int vblur = quad_im.data[y*quad_im.step + x];
1040 
1041  int v = 2*vorig - vblur;
1042  if (v < 0)
1043  v = 0;
1044  if (v > 255)
1045  v = 255;
1046 
1047  quad_im.data[y*quad_im.step + x] = (uint8_t) v;
1048  }
1049  }
1050  }
1051  }
1052  }
1053 
1054 #ifdef APRIL_DEBUG
1055  imwrite("1.1 debug_preprocess.pnm", quad_im);
1056 #endif
1057 
1060  zarray_t *quads = apriltag_quad_thresh(_params, quad_im, contours);
1061 
1062  CV_Assert(quads != NULL);
1063 
1064  // adjust centers of pixels so that they correspond to the
1065  // original full-resolution image.
1066  if (_params->aprilTagQuadDecimate > 1) {
1067  for (int i = 0; i < _zarray_size(quads); i++) {
1068  struct sQuad *q;
1069  _zarray_get_volatile(quads, i, &q);
1070  for (int j = 0; j < 4; j++) {
1071  q->p[j][0] *= _params->aprilTagQuadDecimate;
1072  q->p[j][1] *= _params->aprilTagQuadDecimate;
1073  }
1074  }
1075  }
1076 
1077 #ifdef APRIL_DEBUG
1078  Mat im_quads = im_orig.clone();
1079  im_quads = im_quads*0.5;
1080  srandom(0);
1081 
1082  for (int i = 0; i < _zarray_size(quads); i++) {
1083  struct sQuad *quad;
1084  _zarray_get_volatile(quads, i, &quad);
1085 
1086  const int bias = 100;
1087  int color = bias + (random() % (255-bias));
1088 
1089  line(im_quads, Point(quad->p[0][0], quad->p[0][1]), Point(quad->p[1][0], quad->p[1][1]), color, 1);
1090  line(im_quads, Point(quad->p[1][0], quad->p[1][1]), Point(quad->p[2][0], quad->p[2][1]), color, 1);
1091  line(im_quads, Point(quad->p[2][0], quad->p[2][1]), Point(quad->p[3][0], quad->p[3][1]), color, 1);
1092  line(im_quads, Point(quad->p[3][0], quad->p[3][1]), Point(quad->p[0][0], quad->p[0][1]), color, 1);
1093  }
1094  imwrite("1.2 debug_quads_raw.pnm", im_quads);
1095 #endif
1096 
1099  for (int i = 0; i < _zarray_size(quads); i++) {
1100  struct sQuad *quad;
1101  _zarray_get_volatile(quads, i, &quad);
1102 
1103  std::vector< Point2f > corners;
1104  corners.push_back(Point2f(quad->p[3][0], quad->p[3][1])); //pA
1105  corners.push_back(Point2f(quad->p[0][0], quad->p[0][1])); //pB
1106  corners.push_back(Point2f(quad->p[1][0], quad->p[1][1])); //pC
1107  corners.push_back(Point2f(quad->p[2][0], quad->p[2][1])); //pD
1108 
1109  candidates.push_back(corners);
1110  }
1111 
1112  _zarray_destroy(quads);
1113 }
1114 
1115 
1118 void detectMarkers(InputArray _image, const Ptr<Dictionary> &_dictionary, OutputArrayOfArrays _corners,
1119  OutputArray _ids, const Ptr<DetectorParameters> &_params,
1120  OutputArrayOfArrays _rejectedImgPoints, InputArrayOfArrays camMatrix, InputArrayOfArrays distCoeff) {
1121 
1122  CV_Assert(!_image.empty());
1123 
1124  Mat grey;
1125  _convertToGrey(_image.getMat(), grey);
1126 
1128  vector< vector< Point2f > > candidates;
1129  vector< vector< Point > > contours;
1130  vector< int > ids;
1131 
1133  if(_params->cornerRefinementMethod == CORNER_REFINE_APRILTAG)
1134  _apriltag(grey, _params, candidates, contours);
1135 
1137  else
1138  _detectCandidates(grey, candidates, contours, _params);
1139 
1141  _identifyCandidates(grey, candidates, contours, _dictionary, candidates, ids, _params,
1142  _rejectedImgPoints);
1143 
1145  _filterDetectedMarkers(candidates, ids, contours);
1146 
1147  // copy to output arrays
1148  _copyVector2Output(candidates, _corners);
1149  Mat(ids).copyTo(_ids);
1150 
1152  if( _params->cornerRefinementMethod == CORNER_REFINE_SUBPIX ) {
1153  CV_Assert(_params->cornerRefinementWinSize > 0 && _params->cornerRefinementMaxIterations > 0 &&
1154  _params->cornerRefinementMinAccuracy > 0);
1155 
1157  // for (unsigned int i = 0; i < _corners.cols(); i++) {
1158  // cornerSubPix(grey, _corners.getMat(i),
1159  // Size(params.cornerRefinementWinSize, params.cornerRefinementWinSize),
1160  // Size(-1, -1), TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
1161  // params.cornerRefinementMaxIterations,
1162  // params.cornerRefinementMinAccuracy));
1163  //}
1164 
1165  // this is the parallel call for the previous commented loop (result is equivalent)
1166  parallel_for_(Range(0, _corners.cols()),
1167  MarkerSubpixelParallel(&grey, _corners, _params));
1168  }
1169 
1171  if( _params->cornerRefinementMethod == CORNER_REFINE_CONTOUR){
1172 
1173  if(! _ids.empty()){
1174 
1175  // do corner refinement using the contours for each detected markers
1176  parallel_for_(Range(0, _corners.cols()), MarkerContourParallel(contours, candidates, camMatrix.getMat(), distCoeff.getMat()));
1177 
1178  // copy the corners to the output array
1179  _copyVector2Output(candidates, _corners);
1180  }
1181  }
1182 }
1183 
1184 
1185 
1190 class SinglePoseEstimationParallel : public ParallelLoopBody {
1191  public:
1192  SinglePoseEstimationParallel(Mat& _markerObjPoints, InputArrayOfArrays _corners,
1193  InputArray _cameraMatrix, InputArray _distCoeffs,
1194  Mat& _rvecs, Mat& _tvecs)
1195  : markerObjPoints(_markerObjPoints), corners(_corners), cameraMatrix(_cameraMatrix),
1196  distCoeffs(_distCoeffs), rvecs(_rvecs), tvecs(_tvecs) {}
1197 
1198  void operator()(const Range &range) const CV_OVERRIDE {
1199  const int begin = range.start;
1200  const int end = range.end;
1201 
1202  for(int i = begin; i < end; i++) {
1203  solvePnP(markerObjPoints, corners.getMat(i), cameraMatrix, distCoeffs,
1204  rvecs.at<Vec3d>(i), tvecs.at<Vec3d>(i));
1205  }
1206  }
1207 
1208  private:
1209  SinglePoseEstimationParallel &operator=(const SinglePoseEstimationParallel &); // to quiet MSVC
1210 
1212  InputArrayOfArrays corners;
1214  Mat& rvecs, tvecs;
1215 };
1216 
1217 
1218 
1219 
1222 void estimatePoseSingleMarkers(InputArrayOfArrays _corners, float markerLength,
1223  InputArray _cameraMatrix, InputArray _distCoeffs,
1224  OutputArray _rvecs, OutputArray _tvecs, OutputArray _objPoints) {
1225 
1226  CV_Assert(markerLength > 0);
1227 
1228  Mat markerObjPoints;
1229  _getSingleMarkerObjectPoints(markerLength, markerObjPoints);
1230  int nMarkers = (int)_corners.total();
1231  _rvecs.create(nMarkers, 1, CV_64FC3);
1232  _tvecs.create(nMarkers, 1, CV_64FC3);
1233 
1234  Mat rvecs = _rvecs.getMat(), tvecs = _tvecs.getMat();
1235 
1237  // for (int i = 0; i < nMarkers; i++) {
1238  // solvePnP(markerObjPoints, _corners.getMat(i), _cameraMatrix, _distCoeffs,
1239  // _rvecs.getMat(i), _tvecs.getMat(i));
1240  //}
1241 
1242  // this is the parallel call for the previous commented loop (result is equivalent)
1243  parallel_for_(Range(0, nMarkers),
1244  SinglePoseEstimationParallel(markerObjPoints, _corners, _cameraMatrix,
1245  _distCoeffs, rvecs, tvecs));
1246  if(_objPoints.needed()){
1247  markerObjPoints.convertTo(_objPoints, -1);
1248  }
1249 }
1250 
1251 
1252 
1253 void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners,
1254  InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints) {
1255 
1256  CV_Assert(board->ids.size() == board->objPoints.size());
1257  CV_Assert(detectedIds.total() == detectedCorners.total());
1258 
1259  size_t nDetectedMarkers = detectedIds.total();
1260 
1261  vector< Point3f > objPnts;
1262  objPnts.reserve(nDetectedMarkers);
1263 
1264  vector< Point2f > imgPnts;
1265  imgPnts.reserve(nDetectedMarkers);
1266 
1267  // look for detected markers that belong to the board and get their information
1268  for(unsigned int i = 0; i < nDetectedMarkers; i++) {
1269  int currentId = detectedIds.getMat().ptr< int >(0)[i];
1270  for(unsigned int j = 0; j < board->ids.size(); j++) {
1271  if(currentId == board->ids[j]) {
1272  for(int p = 0; p < 4; p++) {
1273  objPnts.push_back(board->objPoints[j][p]);
1274  imgPnts.push_back(detectedCorners.getMat(i).ptr< Point2f >(0)[p]);
1275  }
1276  }
1277  }
1278  }
1279 
1280  // create output
1281  Mat(objPnts).copyTo(objPoints);
1282  Mat(imgPnts).copyTo(imgPoints);
1283 }
1284 
1285 
1286 
1290 static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArrayOfArrays _detectedCorners,
1291  InputOutputArray _detectedIds, InputArray _cameraMatrix,
1292  InputArray _distCoeffs,
1293  vector< vector< Point2f > >& _undetectedMarkersProjectedCorners,
1294  OutputArray _undetectedMarkersIds) {
1295 
1296  // first estimate board pose with the current avaible markers
1297  Mat rvec, tvec;
1298  int boardDetectedMarkers;
1299  boardDetectedMarkers = aruco::estimatePoseBoard(_detectedCorners, _detectedIds, _board,
1300  _cameraMatrix, _distCoeffs, rvec, tvec);
1301 
1302  // at least one marker from board so rvec and tvec are valid
1303  if(boardDetectedMarkers == 0) return;
1304 
1305  // search undetected markers and project them using the previous pose
1306  vector< vector< Point2f > > undetectedCorners;
1307  vector< int > undetectedIds;
1308  for(unsigned int i = 0; i < _board->ids.size(); i++) {
1309  int foundIdx = -1;
1310  for(unsigned int j = 0; j < _detectedIds.total(); j++) {
1311  if(_board->ids[i] == _detectedIds.getMat().ptr< int >()[j]) {
1312  foundIdx = j;
1313  break;
1314  }
1315  }
1316 
1317  // not detected
1318  if(foundIdx == -1) {
1319  undetectedCorners.push_back(vector< Point2f >());
1320  undetectedIds.push_back(_board->ids[i]);
1321  projectPoints(_board->objPoints[i], rvec, tvec, _cameraMatrix, _distCoeffs,
1322  undetectedCorners.back());
1323  }
1324  }
1325 
1326 
1327  // parse output
1328  Mat(undetectedIds).copyTo(_undetectedMarkersIds);
1329  _undetectedMarkersProjectedCorners = undetectedCorners;
1330 }
1331 
1332 
1333 
1338 static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArrayOfArrays _detectedCorners,
1339  InputOutputArray _detectedIds,
1340  vector< vector< Point2f > >& _undetectedMarkersProjectedCorners,
1341  OutputArray _undetectedMarkersIds) {
1342 
1343 
1344  // check board points are in the same plane, if not, global homography cannot be applied
1345  CV_Assert(_board->objPoints.size() > 0);
1346  CV_Assert(_board->objPoints[0].size() > 0);
1347  float boardZ = _board->objPoints[0][0].z;
1348  for(unsigned int i = 0; i < _board->objPoints.size(); i++) {
1349  for(unsigned int j = 0; j < _board->objPoints[i].size(); j++) {
1350  CV_Assert(boardZ == _board->objPoints[i][j].z);
1351  }
1352  }
1353 
1354  vector< Point2f > detectedMarkersObj2DAll; // Object coordinates (without Z) of all the detected
1355  // marker corners in a single vector
1356  vector< Point2f > imageCornersAll; // Image corners of all detected markers in a single vector
1357  vector< vector< Point2f > > undetectedMarkersObj2D; // Object coordinates (without Z) of all
1358  // missing markers in different vectors
1359  vector< int > undetectedMarkersIds; // ids of missing markers
1360  // find markers included in board, and missing markers from board. Fill the previous vectors
1361  for(unsigned int j = 0; j < _board->ids.size(); j++) {
1362  bool found = false;
1363  for(unsigned int i = 0; i < _detectedIds.total(); i++) {
1364  if(_detectedIds.getMat().ptr< int >()[i] == _board->ids[j]) {
1365  for(int c = 0; c < 4; c++) {
1366  imageCornersAll.push_back(_detectedCorners.getMat(i).ptr< Point2f >()[c]);
1367  detectedMarkersObj2DAll.push_back(
1368  Point2f(_board->objPoints[j][c].x, _board->objPoints[j][c].y));
1369  }
1370  found = true;
1371  break;
1372  }
1373  }
1374  if(!found) {
1375  undetectedMarkersObj2D.push_back(vector< Point2f >());
1376  for(int c = 0; c < 4; c++) {
1377  undetectedMarkersObj2D.back().push_back(
1378  Point2f(_board->objPoints[j][c].x, _board->objPoints[j][c].y));
1379  }
1380  undetectedMarkersIds.push_back(_board->ids[j]);
1381  }
1382  }
1383  if(imageCornersAll.size() == 0) return;
1384 
1385  // get homography from detected markers
1386  Mat transformation = findHomography(detectedMarkersObj2DAll, imageCornersAll);
1387 
1388  _undetectedMarkersProjectedCorners.resize(undetectedMarkersIds.size());
1389 
1390  // for each undetected marker, apply transformation
1391  for(unsigned int i = 0; i < undetectedMarkersObj2D.size(); i++) {
1392  perspectiveTransform(undetectedMarkersObj2D[i], _undetectedMarkersProjectedCorners[i], transformation);
1393  }
1394 
1395  Mat(undetectedMarkersIds).copyTo(_undetectedMarkersIds);
1396 }
1397 
1398 
1399 
1402 void refineDetectedMarkers(InputArray _image, const Ptr<Board> &_board,
1403  InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds,
1404  InputOutputArrayOfArrays _rejectedCorners, InputArray _cameraMatrix,
1405  InputArray _distCoeffs, float minRepDistance, float errorCorrectionRate,
1406  bool checkAllOrders, OutputArray _recoveredIdxs,
1407  const Ptr<DetectorParameters> &_params) {
1408 
1409  CV_Assert(minRepDistance > 0);
1410 
1411  if(_detectedIds.total() == 0 || _rejectedCorners.total() == 0) return;
1412 
1413  DetectorParameters &params = *_params;
1414 
1415  // get projections of missing markers in the board
1416  vector< vector< Point2f > > undetectedMarkersCorners;
1417  vector< int > undetectedMarkersIds;
1418  if(_cameraMatrix.total() != 0) {
1419  // reproject based on camera projection model
1420  _projectUndetectedMarkers(_board, _detectedCorners, _detectedIds, _cameraMatrix, _distCoeffs,
1421  undetectedMarkersCorners, undetectedMarkersIds);
1422 
1423  } else {
1424  // reproject based on global homography
1425  _projectUndetectedMarkers(_board, _detectedCorners, _detectedIds, undetectedMarkersCorners,
1426  undetectedMarkersIds);
1427  }
1428 
1429  // list of missing markers indicating if they have been assigned to a candidate
1430  vector< bool > alreadyIdentified(_rejectedCorners.total(), false);
1431 
1432  // maximum bits that can be corrected
1433  Dictionary &dictionary = *(_board->dictionary);
1434  int maxCorrectionRecalculated =
1435  int(double(dictionary.maxCorrectionBits) * errorCorrectionRate);
1436 
1437  Mat grey;
1438  _convertToGrey(_image, grey);
1439 
1440  // vector of final detected marker corners and ids
1441  vector< Mat > finalAcceptedCorners;
1442  vector< int > finalAcceptedIds;
1443  // fill with the current markers
1444  finalAcceptedCorners.resize(_detectedCorners.total());
1445  finalAcceptedIds.resize(_detectedIds.total());
1446  for(unsigned int i = 0; i < _detectedIds.total(); i++) {
1447  finalAcceptedCorners[i] = _detectedCorners.getMat(i).clone();
1448  finalAcceptedIds[i] = _detectedIds.getMat().ptr< int >()[i];
1449  }
1450  vector< int > recoveredIdxs; // original indexes of accepted markers in _rejectedCorners
1451 
1452  // for each missing marker, try to find a correspondence
1453  for(unsigned int i = 0; i < undetectedMarkersIds.size(); i++) {
1454 
1455  // best match at the moment
1456  int closestCandidateIdx = -1;
1457  double closestCandidateDistance = minRepDistance * minRepDistance + 1;
1458  Mat closestRotatedMarker;
1459 
1460  for(unsigned int j = 0; j < _rejectedCorners.total(); j++) {
1461  if(alreadyIdentified[j]) continue;
1462 
1463  // check distance
1464  double minDistance = closestCandidateDistance + 1;
1465  bool valid = false;
1466  int validRot = 0;
1467  for(int c = 0; c < 4; c++) { // first corner in rejected candidate
1468  double currentMaxDistance = 0;
1469  for(int k = 0; k < 4; k++) {
1470  Point2f rejCorner = _rejectedCorners.getMat(j).ptr< Point2f >()[(c + k) % 4];
1471  Point2f distVector = undetectedMarkersCorners[i][k] - rejCorner;
1472  double cornerDist = distVector.x * distVector.x + distVector.y * distVector.y;
1473  currentMaxDistance = max(currentMaxDistance, cornerDist);
1474  }
1475  // if distance is better than current best distance
1476  if(currentMaxDistance < closestCandidateDistance) {
1477  valid = true;
1478  validRot = c;
1479  minDistance = currentMaxDistance;
1480  }
1481  if(!checkAllOrders) break;
1482  }
1483 
1484  if(!valid) continue;
1485 
1486  // apply rotation
1487  Mat rotatedMarker;
1488  if(checkAllOrders) {
1489  rotatedMarker = Mat(4, 1, CV_32FC2);
1490  for(int c = 0; c < 4; c++)
1491  rotatedMarker.ptr< Point2f >()[c] =
1492  _rejectedCorners.getMat(j).ptr< Point2f >()[(c + 4 + validRot) % 4];
1493  }
1494  else rotatedMarker = _rejectedCorners.getMat(j);
1495 
1496  // last filter, check if inner code is close enough to the assigned marker code
1497  int codeDistance = 0;
1498  // if errorCorrectionRate, dont check code
1499  if(errorCorrectionRate >= 0) {
1500 
1501  // extract bits
1502  Mat bits = _extractBits(
1503  grey, rotatedMarker, dictionary.markerSize, params.markerBorderBits,
1506 
1507  Mat onlyBits =
1508  bits.rowRange(params.markerBorderBits, bits.rows - params.markerBorderBits)
1509  .colRange(params.markerBorderBits, bits.rows - params.markerBorderBits);
1510 
1511  codeDistance =
1512  dictionary.getDistanceToId(onlyBits, undetectedMarkersIds[i], false);
1513  }
1514 
1515  // if everythin is ok, assign values to current best match
1516  if(errorCorrectionRate < 0 || codeDistance < maxCorrectionRecalculated) {
1517  closestCandidateIdx = j;
1518  closestCandidateDistance = minDistance;
1519  closestRotatedMarker = rotatedMarker;
1520  }
1521  }
1522 
1523  // if at least one good match, we have rescue the missing marker
1524  if(closestCandidateIdx >= 0) {
1525 
1526  // subpixel refinement
1527  if(_params->cornerRefinementMethod == CORNER_REFINE_SUBPIX) {
1528  CV_Assert(params.cornerRefinementWinSize > 0 &&
1529  params.cornerRefinementMaxIterations > 0 &&
1530  params.cornerRefinementMinAccuracy > 0);
1531  cornerSubPix(grey, closestRotatedMarker,
1532  Size(params.cornerRefinementWinSize, params.cornerRefinementWinSize),
1533  Size(-1, -1), TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
1535  params.cornerRefinementMinAccuracy));
1536  }
1537 
1538  // remove from rejected
1539  alreadyIdentified[closestCandidateIdx] = true;
1540 
1541  // add to detected
1542  finalAcceptedCorners.push_back(closestRotatedMarker);
1543  finalAcceptedIds.push_back(undetectedMarkersIds[i]);
1544 
1545  // add the original index of the candidate
1546  recoveredIdxs.push_back(closestCandidateIdx);
1547  }
1548  }
1549 
1550  // parse output
1551  if(finalAcceptedIds.size() != _detectedIds.total()) {
1552  _detectedCorners.clear();
1553  _detectedIds.clear();
1554 
1555  // parse output
1556  Mat(finalAcceptedIds).copyTo(_detectedIds);
1557 
1558  _detectedCorners.create((int)finalAcceptedCorners.size(), 1, CV_32FC2);
1559  for(unsigned int i = 0; i < finalAcceptedCorners.size(); i++) {
1560  _detectedCorners.create(4, 1, CV_32FC2, i, true);
1561  for(int j = 0; j < 4; j++) {
1562  _detectedCorners.getMat(i).ptr< Point2f >()[j] =
1563  finalAcceptedCorners[i].ptr< Point2f >()[j];
1564  }
1565  }
1566 
1567  // recalculate _rejectedCorners based on alreadyIdentified
1568  vector< Mat > finalRejected;
1569  for(unsigned int i = 0; i < alreadyIdentified.size(); i++) {
1570  if(!alreadyIdentified[i]) {
1571  finalRejected.push_back(_rejectedCorners.getMat(i).clone());
1572  }
1573  }
1574 
1575  _rejectedCorners.clear();
1576  _rejectedCorners.create((int)finalRejected.size(), 1, CV_32FC2);
1577  for(unsigned int i = 0; i < finalRejected.size(); i++) {
1578  _rejectedCorners.create(4, 1, CV_32FC2, i, true);
1579  for(int j = 0; j < 4; j++) {
1580  _rejectedCorners.getMat(i).ptr< Point2f >()[j] =
1581  finalRejected[i].ptr< Point2f >()[j];
1582  }
1583  }
1584 
1585  if(_recoveredIdxs.needed()) {
1586  Mat(recoveredIdxs).copyTo(_recoveredIdxs);
1587  }
1588  }
1589 }
1590 
1591 
1592 
1593 
1596 int estimatePoseBoard(InputArrayOfArrays _corners, InputArray _ids, const Ptr<Board> &board,
1597  InputArray _cameraMatrix, InputArray _distCoeffs, OutputArray _rvec,
1598  OutputArray _tvec, bool useExtrinsicGuess) {
1599 
1600  CV_Assert(_corners.total() == _ids.total());
1601 
1602  // get object and image points for the solvePnP function
1603  Mat objPoints, imgPoints;
1604  getBoardObjectAndImagePoints(board, _corners, _ids, objPoints, imgPoints);
1605 
1606  CV_Assert(imgPoints.total() == objPoints.total());
1607 
1608  if(objPoints.total() == 0) // 0 of the detected markers in board
1609  return 0;
1610 
1611  solvePnP(objPoints, imgPoints, _cameraMatrix, _distCoeffs, _rvec, _tvec, useExtrinsicGuess);
1612 
1613  // divide by four since all the four corners are concatenated in the array for each marker
1614  return (int)objPoints.total() / 4;
1615 }
1616 
1617 
1618 
1619 
1622 void GridBoard::draw(Size outSize, OutputArray _img, int marginSize, int borderBits) {
1623  _drawPlanarBoardImpl(this, outSize, _img, marginSize, borderBits);
1624 }
1625 
1626 
1629 Ptr<Board> Board::create(InputArrayOfArrays objPoints, const Ptr<Dictionary> &dictionary, InputArray ids) {
1630 
1631  CV_Assert(objPoints.total() == ids.total());
1632  CV_Assert(objPoints.type() == CV_32FC3 || objPoints.type() == CV_32FC1);
1633 
1634  std::vector< std::vector< Point3f > > obj_points_vector;
1635  for (unsigned int i = 0; i < objPoints.total(); i++) {
1636  std::vector<Point3f> corners;
1637  Mat corners_mat = objPoints.getMat(i);
1638 
1639  if(corners_mat.type() == CV_32FC1)
1640  corners_mat = corners_mat.reshape(3);
1641  CV_Assert(corners_mat.total() == 4);
1642 
1643  for (int j = 0; j < 4; j++) {
1644  corners.push_back(corners_mat.at<Point3f>(j));
1645  }
1646  obj_points_vector.push_back(corners);
1647  }
1648 
1649  Ptr<Board> res = makePtr<Board>();
1650  ids.copyTo(res->ids);
1651  res->objPoints = obj_points_vector;
1652  res->dictionary = cv::makePtr<Dictionary>(dictionary);
1653  return res;
1654 }
1655 
1658 Ptr<GridBoard> GridBoard::create(int markersX, int markersY, float markerLength, float markerSeparation,
1659  const Ptr<Dictionary> &dictionary, int firstMarker) {
1660 
1661  CV_Assert(markersX > 0 && markersY > 0 && markerLength > 0 && markerSeparation > 0);
1662 
1663  Ptr<GridBoard> res = makePtr<GridBoard>();
1664 
1665  res->_markersX = markersX;
1666  res->_markersY = markersY;
1667  res->_markerLength = markerLength;
1668  res->_markerSeparation = markerSeparation;
1669  res->dictionary = dictionary;
1670 
1671  size_t totalMarkers = (size_t) markersX * markersY;
1672  res->ids.resize(totalMarkers);
1673  res->objPoints.reserve(totalMarkers);
1674 
1675  // fill ids with first identifiers
1676  for(unsigned int i = 0; i < totalMarkers; i++) {
1677  res->ids[i] = i + firstMarker;
1678  }
1679 
1680  // calculate Board objPoints
1681  float maxY = (float)markersY * markerLength + (markersY - 1) * markerSeparation;
1682  for(int y = 0; y < markersY; y++) {
1683  for(int x = 0; x < markersX; x++) {
1684  vector< Point3f > corners;
1685  corners.resize(4);
1686  corners[0] = Point3f(x * (markerLength + markerSeparation),
1687  maxY - y * (markerLength + markerSeparation), 0);
1688  corners[1] = corners[0] + Point3f(markerLength, 0, 0);
1689  corners[2] = corners[0] + Point3f(markerLength, -markerLength, 0);
1690  corners[3] = corners[0] + Point3f(0, -markerLength, 0);
1691  res->objPoints.push_back(corners);
1692  }
1693  }
1694 
1695  return res;
1696 }
1697 
1698 
1699 
1702 void drawDetectedMarkers(InputOutputArray _image, InputArrayOfArrays _corners,
1703  InputArray _ids, Scalar borderColor) {
1704 
1705 
1706  CV_Assert(_image.getMat().total() != 0 &&
1707  (_image.getMat().channels() == 1 || _image.getMat().channels() == 3));
1708  CV_Assert((_corners.total() == _ids.total()) || _ids.total() == 0);
1709 
1710  // calculate colors
1711  Scalar textColor, cornerColor;
1712  textColor = cornerColor = borderColor;
1713  swap(textColor.val[0], textColor.val[1]); // text color just sawp G and R
1714  swap(cornerColor.val[1], cornerColor.val[2]); // corner color just sawp G and B
1715 
1716  int nMarkers = (int)_corners.total();
1717  for(int i = 0; i < nMarkers; i++) {
1718  Mat currentMarker = _corners.getMat(i);
1719  CV_Assert(currentMarker.total() == 4 && currentMarker.type() == CV_32FC2);
1720 
1721  // draw marker sides
1722  for(int j = 0; j < 4; j++) {
1723  Point2f p0, p1;
1724  p0 = currentMarker.ptr< Point2f >(0)[j];
1725  p1 = currentMarker.ptr< Point2f >(0)[(j + 1) % 4];
1726  line(_image, p0, p1, borderColor, 1);
1727  }
1728  // draw first corner mark
1729  rectangle(_image, currentMarker.ptr< Point2f >(0)[0] - Point2f(3, 3),
1730  currentMarker.ptr< Point2f >(0)[0] + Point2f(3, 3), cornerColor, 1, LINE_AA);
1731 
1732  // draw ID
1733  if(_ids.total() != 0) {
1734  Point2f cent(0, 0);
1735  for(int p = 0; p < 4; p++)
1736  cent += currentMarker.ptr< Point2f >(0)[p];
1737  cent = cent / 4.;
1738  stringstream s;
1739  s << "id=" << _ids.getMat().ptr< int >(0)[i];
1740  putText(_image, s.str(), cent, FONT_HERSHEY_SIMPLEX, 0.5, textColor, 2);
1741  }
1742  }
1743 }
1744 
1745 
1746 
1749 void drawAxis(InputOutputArray _image, InputArray _cameraMatrix, InputArray _distCoeffs, InputArray _rvec,
1750  InputArray _tvec, float length)
1751 {
1752  /* no-op since we're using our own _drawAxis routine */
1753  /*drawFrameAxes(_image, _cameraMatrix, _distCoeffs, _rvec, _tvec, length, 3);*/
1754 }
1755 
1758 void drawMarker(const Ptr<Dictionary> &dictionary, int id, int sidePixels, OutputArray _img, int borderBits) {
1759  dictionary->drawMarker(id, sidePixels, _img, borderBits);
1760 }
1761 
1762 
1763 
1764 void _drawPlanarBoardImpl(Board *_board, Size outSize, OutputArray _img, int marginSize,
1765  int borderBits) {
1766 
1767  /* NOTE: OpenCV v<3.3 does not have .empty() as a Size member */
1768  CV_Assert(outSize.height > 0 && outSize.width > 0);
1769  CV_Assert(marginSize >= 0);
1770 
1771  _img.create(outSize, CV_8UC1);
1772  Mat out = _img.getMat();
1773  out.setTo(Scalar::all(255));
1774  out.adjustROI(-marginSize, -marginSize, -marginSize, -marginSize);
1775 
1776  // calculate max and min values in XY plane
1777  CV_Assert(_board->objPoints.size() > 0);
1778  float minX, maxX, minY, maxY;
1779  minX = maxX = _board->objPoints[0][0].x;
1780  minY = maxY = _board->objPoints[0][0].y;
1781 
1782  for(unsigned int i = 0; i < _board->objPoints.size(); i++) {
1783  for(int j = 0; j < 4; j++) {
1784  minX = min(minX, _board->objPoints[i][j].x);
1785  maxX = max(maxX, _board->objPoints[i][j].x);
1786  minY = min(minY, _board->objPoints[i][j].y);
1787  maxY = max(maxY, _board->objPoints[i][j].y);
1788  }
1789  }
1790 
1791  float sizeX = maxX - minX;
1792  float sizeY = maxY - minY;
1793 
1794  // proportion transformations
1795  float xReduction = sizeX / float(out.cols);
1796  float yReduction = sizeY / float(out.rows);
1797 
1798  // determine the zone where the markers are placed
1799  if(xReduction > yReduction) {
1800  int nRows = int(sizeY / xReduction);
1801  int rowsMargins = (out.rows - nRows) / 2;
1802  out.adjustROI(-rowsMargins, -rowsMargins, 0, 0);
1803  } else {
1804  int nCols = int(sizeX / yReduction);
1805  int colsMargins = (out.cols - nCols) / 2;
1806  out.adjustROI(0, 0, -colsMargins, -colsMargins);
1807  }
1808 
1809  // now paint each marker
1810  Dictionary &dictionary = *(_board->dictionary);
1811  Mat marker;
1812  Point2f outCorners[3];
1813  Point2f inCorners[3];
1814  for(unsigned int m = 0; m < _board->objPoints.size(); m++) {
1815  // transform corners to markerZone coordinates
1816  for(int j = 0; j < 3; j++) {
1817  Point2f pf = Point2f(_board->objPoints[m][j].x, _board->objPoints[m][j].y);
1818  // move top left to 0, 0
1819  pf -= Point2f(minX, minY);
1820  pf.x = pf.x / sizeX * float(out.cols);
1821  pf.y = (1.0f - pf.y / sizeY) * float(out.rows);
1822  outCorners[j] = pf;
1823  }
1824 
1825  // get marker
1826  Size dst_sz(outCorners[2] - outCorners[0]); // assuming CCW order
1827  dst_sz.width = dst_sz.height = std::min(dst_sz.width, dst_sz.height); //marker should be square
1828  dictionary.drawMarker(_board->ids[m], dst_sz.width, marker, borderBits);
1829 
1830  if((outCorners[0].y == outCorners[1].y) && (outCorners[1].x == outCorners[2].x)) {
1831  // marker is aligned to image axes
1832  marker.copyTo(out(Rect(outCorners[0], dst_sz)));
1833  continue;
1834  }
1835 
1836  // interpolate tiny marker to marker position in markerZone
1837  inCorners[0] = Point2f(-0.5f, -0.5f);
1838  inCorners[1] = Point2f(marker.cols - 0.5f, -0.5f);
1839  inCorners[2] = Point2f(marker.cols - 0.5f, marker.rows - 0.5f);
1840 
1841  // remove perspective
1842  Mat transformation = getAffineTransform(inCorners, outCorners);
1843  warpAffine(marker, out, transformation, out.size(), INTER_LINEAR,
1844  BORDER_TRANSPARENT);
1845  }
1846 }
1847 
1848 
1849 
1852 void drawPlanarBoard(const Ptr<Board> &_board, Size outSize, OutputArray _img, int marginSize,
1853  int borderBits) {
1854  _drawPlanarBoardImpl(_board, outSize, _img, marginSize, borderBits);
1855 }
1856 
1857 
1858 
1861 double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter,
1862  const Ptr<Board> &board, Size imageSize, InputOutputArray _cameraMatrix,
1863  InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs,
1864  OutputArrayOfArrays _tvecs,
1865  OutputArray _stdDeviationsIntrinsics,
1866  OutputArray _stdDeviationsExtrinsics,
1867  OutputArray _perViewErrors,
1868  int flags, TermCriteria criteria) {
1869 
1870  // for each frame, get properly processed imagePoints and objectPoints for the calibrateCamera
1871  // function
1872  vector< Mat > processedObjectPoints, processedImagePoints;
1873  size_t nFrames = _counter.total();
1874  int markerCounter = 0;
1875  for(size_t frame = 0; frame < nFrames; frame++) {
1876  int nMarkersInThisFrame = _counter.getMat().ptr< int >()[frame];
1877  vector< Mat > thisFrameCorners;
1878  vector< int > thisFrameIds;
1879 
1880  CV_Assert(nMarkersInThisFrame > 0);
1881 
1882  thisFrameCorners.reserve((size_t) nMarkersInThisFrame);
1883  thisFrameIds.reserve((size_t) nMarkersInThisFrame);
1884  for(int j = markerCounter; j < markerCounter + nMarkersInThisFrame; j++) {
1885  thisFrameCorners.push_back(_corners.getMat(j));
1886  thisFrameIds.push_back(_ids.getMat().ptr< int >()[j]);
1887  }
1888  markerCounter += nMarkersInThisFrame;
1889  Mat currentImgPoints, currentObjPoints;
1890  getBoardObjectAndImagePoints(board, thisFrameCorners, thisFrameIds, currentObjPoints,
1891  currentImgPoints);
1892  if(currentImgPoints.total() > 0 && currentObjPoints.total() > 0) {
1893  processedImagePoints.push_back(currentImgPoints);
1894  processedObjectPoints.push_back(currentObjPoints);
1895  }
1896  }
1897 
1898  return calibrateCamera(processedObjectPoints, processedImagePoints, imageSize, _cameraMatrix,
1899  _distCoeffs, _rvecs, _tvecs, _stdDeviationsIntrinsics, _stdDeviationsExtrinsics,
1900  _perViewErrors, flags, criteria);
1901 }
1902 
1903 
1904 
1907 double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter,
1908  const Ptr<Board> &board, Size imageSize, InputOutputArray _cameraMatrix,
1909  InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs,
1910  OutputArrayOfArrays _tvecs, int flags, TermCriteria criteria) {
1911  return calibrateCameraAruco(_corners, _ids, _counter, board, imageSize, _cameraMatrix, _distCoeffs, _rvecs, _tvecs,
1912  noArray(), noArray(), noArray(), flags, criteria);
1913 }
1914 
1915 
1916 
1917 }
1918 }
static CV_WRAP Ptr< GridBoard > create(int markersX, int markersY, float markerLength, float markerSeparation, const Ptr< Dictionary > &dictionary, int firstMarker=0)
Create a GridBoard object.
Definition: aruco.cpp:1658
d
static Point3f _interpolate2Dline(const std::vector< cv::Point2f > &nContours)
Definition: aruco.cpp:813
MarkerContourParallel(vector< vector< Point > > &_contours, vector< vector< Point2f > > &_candidates, const Mat &_camMatrix, const Mat &_distCoeff)
Definition: aruco.cpp:960
CV_PROP_RW double minOtsuStdDev
Definition: aruco.hpp:174
ArUco approach and refine the corners locations using the contour-points line fitting.
Definition: aruco.hpp:84
CV_EXPORTS_W void getBoardObjectAndImagePoints(const Ptr< Board > &board, InputArrayOfArrays detectedCorners, InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints)
Given a board configuration and a set of detected markers, returns the corresponding image points and...
Definition: aruco.cpp:1253
DetectInitialCandidatesParallel(const Mat *_grey, vector< vector< vector< Point2f > > > *_candidatesArrays, vector< vector< vector< Point > > > *_contoursArrays, const Ptr< DetectorParameters > &_params)
Definition: aruco.cpp:289
const Ptr< DetectorParameters > & params
Definition: aruco.cpp:806
Parameters for the detectMarker process:
Definition: aruco.hpp:150
static void _copyVector2Output(vector< vector< Point2f > > &vec, OutputArrayOfArrays out)
Copy the contents of a corners vector to an OutputArray, settings its size.
Definition: aruco.cpp:591
static void _reorderCandidatesCorners(vector< vector< Point2f > > &candidates)
Assure order of candidate corners is clockwise direction.
Definition: aruco.cpp:198
static void _distortPoints(vector< cv::Point2f > &in, const Mat &camMatrix, const Mat &distCoeff)
Definition: aruco.cpp:864
static void _detectInitialCandidates(const Mat &grey, vector< vector< Point2f > > &candidates, vector< vector< Point > > &contours, const Ptr< DetectorParameters > &params)
Initial steps on finding square candidates.
Definition: aruco.cpp:328
CV_PROP_RW int perspectiveRemovePixelPerCell
Definition: aruco.hpp:171
static void _zarray_destroy(zarray_t *za)
Definition: zarray.hpp:55
MarkerSubpixelParallel(const Mat *_grey, OutputArrayOfArrays _corners, const Ptr< DetectorParameters > &_params)
Definition: aruco.cpp:784
f
static void _projectUndetectedMarkers(const Ptr< Board > &_board, InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds, InputArray _cameraMatrix, InputArray _distCoeffs, vector< vector< Point2f > > &_undetectedMarkersProjectedCorners, OutputArray _undetectedMarkersIds)
Definition: aruco.cpp:1290
ArUco approach and refine the corners locations using corner subpixel accuracy.
Definition: aruco.hpp:83
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray cameraMatrix
Definition: charuco.hpp:245
InputArrayOfArrays const Ptr< CharucoBoard > Size imageSize
Definition: charuco.hpp:245
const Ptr< Dictionary > & dictionary
Definition: aruco.cpp:580
static CV_WRAP Ptr< Board > create(InputArrayOfArrays objPoints, const Ptr< Dictionary > &dictionary, InputArray ids)
Provide way to create Board by passing necessary data. Specially needed in Python.
Definition: aruco.cpp:1629
static Mat _extractBits(InputArray _image, InputArray _corners, int markerSize, int markerBorderBits, int cellSize, double cellMarginRate, double minStdDevOtsu)
Given an input image and candidate corners, extract the bits of the candidate, including the border b...
Definition: aruco.cpp:401
XmlRpcServer s
CV_WRAP void drawMarker(int id, int sidePixels, OutputArray _img, int borderBits=1) const
Draw a canonical marker image.
Definition: dictionary.cpp:166
const Ptr< DetectorParameters > & params
Definition: aruco.cpp:321
CV_PROP_RW double minMarkerDistanceRate
Definition: aruco.hpp:165
void operator()(const Range &range) const CV_OVERRIDE
Definition: aruco.cpp:788
Definition: charuco.hpp:47
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray distCoeffs
Definition: charuco.hpp:245
tf::Vector3 Point
float p[4][2]
Definition: zarray.hpp:25
length
Definition: genmap.py:42
CV_PROP_RW int cornerRefinementMaxIterations
Definition: aruco.hpp:168
geometry_msgs::TransformStamped t
Tag and corners detection based on the ArUco approach.
Definition: aruco.hpp:82
zarray_t * apriltag_quad_thresh(const Ptr< DetectorParameters > &parameters, const Mat &mImg, std::vector< std::vector< Point > > &contours)
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int TermCriteria criteria
Definition: charuco.hpp:250
static void _apriltag(Mat im_orig, const Ptr< DetectorParameters > &_params, std::vector< std::vector< Point2f > > &candidates, std::vector< std::vector< Point > > &contours)
Definition: aruco.cpp:998
CV_PROP Ptr< Dictionary > dictionary
the dictionary of markers employed for this board
Definition: aruco.hpp:289
Tag and corners detection based on the AprilTag 2 approach .
Definition: aruco.hpp:85
vector< vector< vector< Point2f > > > * candidatesArrays
Definition: aruco.cpp:319
CV_PROP_RW int cornerRefinementWinSize
Definition: aruco.hpp:167
CV_PROP_RW int minDistanceToBorder
Definition: aruco.hpp:164
OutputArrayOfArrays corners
Definition: aruco.cpp:805
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
static void _refineCandidateLines(std::vector< Point > &nContours, std::vector< Point2f > &nCorners, const Mat &camMatrix, const Mat &distCoeff)
Definition: aruco.cpp:886
vector< vector< Point2f > > & candidates
Definition: aruco.cpp:579
static void _threshold(InputArray _in, OutputArray _out, int winSize, double constant)
Threshold input image using adaptive thresholding.
Definition: aruco.cpp:119
Board of markers.
Definition: aruco.hpp:272
MarkerContourParallel & operator=(const MarkerContourParallel &)
Definition: aruco.cpp:971
const Ptr< DetectorParameters > & params
Definition: aruco.cpp:583
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int flags
Definition: charuco.hpp:249
void threshold(const Mat mIm, const Ptr< DetectorParameters > &parameters, Mat &mThresh)
static void _convertToGrey(InputArray _in, OutputArray _out)
Convert input image to gray if it is a 3-channels image.
Definition: aruco.cpp:105
vector< vector< Point > > & contours
Definition: aruco.cpp:975
static void _detectCandidates(InputArray _image, vector< vector< Point2f > > &candidatesOut, vector< vector< Point > > &contoursOut, const Ptr< DetectorParameters > &_params)
Detect square candidates in the input image.
Definition: aruco.cpp:373
double min(double a, double b)
CV_EXPORTS_W double calibrateCameraAruco(InputArrayOfArrays corners, InputArray ids, InputArray counter, const Ptr< Board > &board, Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs, OutputArrayOfArrays rvecs=noArray(), OutputArrayOfArrays tvecs=noArray(), int flags=0, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, DBL_EPSILON))
It&#39;s the same function as calibrateCameraAruco but without calibration error estimation.
Definition: aruco.cpp:1907
static Point2f _getCrossPoint(Point3f nLine1, Point3f nLine2)
Definition: aruco.cpp:858
static void _filterTooCloseCandidates(const vector< vector< Point2f > > &candidatesIn, vector< vector< Point2f > > &candidatesOut, const vector< vector< Point > > &contoursIn, vector< vector< Point > > &contoursOut, double minMarkerDistanceRate)
Check candidates that are too close to each other and remove the smaller one.
Definition: aruco.cpp:217
CV_PROP std::vector< std::vector< Point3f > > objPoints
Definition: aruco.hpp:286
static void _zarray_get_volatile(const zarray_t *za, int idx, void *p)
Definition: zarray.hpp:122
void _drawPlanarBoardImpl(Board *board, Size outSize, OutputArray img, int marginSize=0, int borderBits=1)
Implementation of drawPlanarBoard that accepts a raw Board pointer.
Definition: aruco.cpp:1764
CV_PROP_RW double minCornerDistanceRate
Definition: aruco.hpp:163
static bool _identifyOneCandidate(const Ptr< Dictionary > &dictionary, InputArray _image, vector< Point2f > &_corners, int &idx, const Ptr< DetectorParameters > &params)
Tries to identify one candidate given the dictionary.
Definition: aruco.cpp:497
CV_PROP_RW int markerBorderBits
Definition: aruco.hpp:170
CV_PROP_RW double cornerRefinementMinAccuracy
Definition: aruco.hpp:169
CV_PROP_RW double perspectiveRemoveIgnoredMarginPerCell
Definition: aruco.hpp:172
CV_EXPORTS_W void refineDetectedMarkers(InputArray image, const Ptr< Board > &board, InputOutputArrayOfArrays detectedCorners, InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners, InputArray cameraMatrix=noArray(), InputArray distCoeffs=noArray(), float minRepDistance=10.f, float errorCorrectionRate=3.f, bool checkAllOrders=true, OutputArray recoveredIdxs=noArray(), const Ptr< DetectorParameters > &parameters=DetectorParameters::create())
Refind not detected markers based on the already detected and the board layout.
Definition: aruco.cpp:1402
void operator()(const Range &range) const CV_OVERRIDE
Definition: aruco.cpp:963
CV_EXPORTS_W void drawMarker(const Ptr< Dictionary > &dictionary, int id, int sidePixels, OutputArray img, int borderBits=1)
Draw a canonical marker image.
Definition: aruco.cpp:1758
CV_EXPORTS_W void drawDetectedMarkers(InputOutputArray image, InputArrayOfArrays corners, InputArray ids=noArray(), Scalar borderColor=Scalar(0, 255, 0))
Draw detected markers in image.
Definition: aruco.cpp:1702
static int _zarray_size(const zarray_t *za)
Definition: zarray.hpp:70
void operator()(const Range &range) const CV_OVERRIDE
Definition: aruco.cpp:562
IdentifyCandidatesParallel(const Mat &_grey, vector< vector< Point2f > > &_candidates, const Ptr< Dictionary > &_dictionary, vector< int > &_idsTmp, vector< char > &_validCandidates, const Ptr< DetectorParameters > &_params)
Definition: aruco.cpp:555
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays rvecs
Definition: charuco.hpp:245
CV_EXPORTS_W void estimatePoseSingleMarkers(InputArrayOfArrays corners, float markerLength, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvecs, OutputArray tvecs, OutputArray _objPoints=noArray())
Pose estimation for single markers.
Definition: aruco.cpp:1222
vector< vector< Point2f > > & candidates
Definition: aruco.cpp:976
static CV_WRAP Ptr< DetectorParameters > create()
Create a new set of DetectorParameters with default values.
Definition: aruco.cpp:96
static int _getBorderErrors(const Mat &bits, int markerSize, int borderSize)
Return number of erroneous bits in border, i.e. number of white bits in border.
Definition: aruco.cpp:471
static void _filterDetectedMarkers(vector< vector< Point2f > > &_corners, vector< int > &_ids, vector< vector< Point > > &_contours)
Final filter of markers after its identification.
Definition: aruco.cpp:688
CV_WRAP void draw(Size outSize, OutputArray img, int marginSize=0, int borderBits=1)
Draw a GridBoard.
Definition: aruco.cpp:1622
CV_EXPORTS_W int estimatePoseBoard(InputArrayOfArrays corners, InputArray ids, const Ptr< Board > &board, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false)
Pose estimation for a board of markers.
Definition: aruco.cpp:1596
void operator()(const Range &range) const CV_OVERRIDE
Definition: aruco.cpp:296
InputArray ids
Definition: aruco.hpp:569
void operator()(const Range &range) const CV_OVERRIDE
Definition: aruco.cpp:1198
CV_PROP_RW double errorCorrectionRate
Definition: aruco.hpp:175
int markerSize
Definition: dictionary.hpp:183
static void _getSingleMarkerObjectPoints(float markerLength, OutputArray _objPoints)
Return object points for the system centered in a single marker, given the marker length...
Definition: aruco.cpp:762
CV_PROP std::vector< int > ids
Definition: aruco.hpp:293
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays tvecs
Definition: charuco.hpp:245
CV_EXPORTS_W void detectMarkers(InputArray image, const Ptr< Dictionary > &dictionary, OutputArrayOfArrays corners, OutputArray ids, const Ptr< DetectorParameters > &parameters=DetectorParameters::create(), OutputArrayOfArrays rejectedImgPoints=noArray(), InputArray cameraMatrix=noArray(), InputArray distCoeff=noArray())
Basic marker detection.
void swap(scoped_ptr< T > &, scoped_ptr< T > &)
static void _findMarkerContours(InputArray _in, vector< vector< Point2f > > &candidates, vector< vector< Point > > &contoursOut, double minPerimeterRate, double maxPerimeterRate, double accuracyRate, double minCornerDistanceRate, int minDistanceToBorder)
Given a tresholded image, find the contours, calculate their polygonal approximation and take those t...
Definition: aruco.cpp:131
double max(double a, double b)
IMETHOD void random(Vector &a)
static void _identifyCandidates(InputArray _image, vector< vector< Point2f > > &_candidates, vector< vector< Point > > &_contours, const Ptr< Dictionary > &_dictionary, vector< vector< Point2f > > &_accepted, vector< int > &ids, const Ptr< DetectorParameters > &params, OutputArrayOfArrays _rejected=noArray())
Identify square candidates according to a marker dictionary.
Definition: aruco.cpp:626
Dictionary/Set of markers. It contains the inner codification.
Definition: dictionary.hpp:61
vector< vector< vector< Point > > > * contoursArrays
Definition: aruco.cpp:320
first
Definition: genmap.py:43
SinglePoseEstimationParallel(Mat &_markerObjPoints, InputArrayOfArrays _corners, InputArray _cameraMatrix, InputArray _distCoeffs, Mat &_rvecs, Mat &_tvecs)
Definition: aruco.cpp:1192
InputArrayOfArrays const Ptr< CharucoBoard > & board
Definition: charuco.hpp:245
CV_EXPORTS_W void drawAxis(InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs, InputArray rvec, InputArray tvec, float length)
Draw coordinate system axis from pose estimation.
Definition: aruco.cpp:1749
CV_EXPORTS_W void drawPlanarBoard(const Ptr< Board > &board, Size outSize, OutputArray img, int marginSize=0, int borderBits=1)
Draw a planar board.
Definition: aruco.cpp:1852


aruco_pose
Author(s): Oleg Kalachev
autogenerated on Mon Feb 28 2022 22:08:24