aruco.cpp 72.1 KB
Newer Older
S. Garrido's avatar
S. Garrido committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43
/*
By downloading, copying, installing or using the software you agree to this
license. If you do not agree to this license, do not download, install,
copy or use the software.

                          License Agreement
               For Open Source Computer Vision Library
                       (3-clause BSD License)

Copyright (C) 2013, OpenCV Foundation, all rights reserved.
Third party copyrights are property of their respective owners.

Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:

  * Redistributions of source code must retain the above copyright notice,
    this list of conditions and the following disclaimer.

  * Redistributions in binary form must reproduce the above copyright notice,
    this list of conditions and the following disclaimer in the documentation
    and/or other materials provided with the distribution.

  * Neither the names of the copyright holders nor the names of the contributors
    may be used to endorse or promote products derived from this software
    without specific prior written permission.

This software is provided by the copyright holders and contributors "as is" and
any express or implied warranties, including, but not limited to, the implied
warranties of merchantability and fitness for a particular purpose are
disclaimed. In no event shall copyright holders or contributors be liable for
any direct, indirect, incidental, special, exemplary, or consequential damages
(including, but not limited to, procurement of substitute goods or services;
loss of use, data, or profits; or business interruption) however caused
and on any theory of liability, whether in contract, strict liability,
or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/

#include "precomp.hpp"
#include "opencv2/aruco.hpp"
#include <opencv2/core.hpp>
#include <opencv2/imgproc.hpp>

44 45 46 47 48 49 50 51
#include "apriltag_quad_thresh.hpp"
#include "zarray.hpp"

//#define APRIL_DEBUG
#ifdef APRIL_DEBUG
#include "opencv2/imgcodecs.hpp"
#endif

S. Garrido's avatar
S. Garrido committed
52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71
namespace cv {
namespace aruco {

using namespace std;


/**
  *
  */
DetectorParameters::DetectorParameters()
    : adaptiveThreshWinSizeMin(3),
      adaptiveThreshWinSizeMax(23),
      adaptiveThreshWinSizeStep(10),
      adaptiveThreshConstant(7),
      minMarkerPerimeterRate(0.03),
      maxMarkerPerimeterRate(4.),
      polygonalApproxAccuracyRate(0.03),
      minCornerDistanceRate(0.05),
      minDistanceToBorder(3),
      minMarkerDistanceRate(0.05),
72
      cornerRefinementMethod(CORNER_REFINE_NONE),
S. Garrido's avatar
S. Garrido committed
73 74 75 76 77 78
      cornerRefinementWinSize(5),
      cornerRefinementMaxIterations(30),
      cornerRefinementMinAccuracy(0.1),
      markerBorderBits(1),
      perspectiveRemovePixelPerCell(4),
      perspectiveRemoveIgnoredMarginPerCell(0.13),
79
      maxErroneousBitsInBorderRate(0.35),
S. Garrido's avatar
S. Garrido committed
80
      minOtsuStdDev(5.0),
81 82 83 84 85 86 87 88
      errorCorrectionRate(0.6),
      aprilTagQuadDecimate(0.0),
      aprilTagQuadSigma(0.0),
      aprilTagMinClusterPixels(5),
      aprilTagMaxNmaxima(10),
      aprilTagCriticalRad( (float)(10* CV_PI /180) ),
      aprilTagMaxLineFitMse(10.0),
      aprilTagMinWhiteBlackDiff(5),
89 90
      aprilTagDeglitch(0),
      detectInvertedMarker(false){}
S. Garrido's avatar
S. Garrido committed
91 92


93 94 95 96 97 98 99 100 101
/**
  * @brief Create a new set of DetectorParameters with default values.
  */
Ptr<DetectorParameters> DetectorParameters::create() {
    Ptr<DetectorParameters> params = makePtr<DetectorParameters>();
    return params;
}


S. Garrido's avatar
S. Garrido committed
102 103 104 105 106
/**
  * @brief Convert input image to gray if it is a 3-channels image
  */
static void _convertToGrey(InputArray _in, OutputArray _out) {

Suleyman TURKMEN's avatar
Suleyman TURKMEN committed
107
    CV_Assert(_in.type() == CV_8UC1 || _in.type() == CV_8UC3);
S. Garrido's avatar
S. Garrido committed
108

Suleyman TURKMEN's avatar
Suleyman TURKMEN committed
109 110
    if(_in.type() == CV_8UC3)
        cvtColor(_in, _out, COLOR_BGR2GRAY);
S. Garrido's avatar
S. Garrido committed
111
    else
Suleyman TURKMEN's avatar
Suleyman TURKMEN committed
112
        _in.copyTo(_out);
S. Garrido's avatar
S. Garrido committed
113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147
}


/**
  * @brief Threshold input image using adaptive thresholding
  */
static void _threshold(InputArray _in, OutputArray _out, int winSize, double constant) {

    CV_Assert(winSize >= 3);
    if(winSize % 2 == 0) winSize++; // win size must be odd
    adaptiveThreshold(_in, _out, 255, ADAPTIVE_THRESH_MEAN_C, THRESH_BINARY_INV, winSize, constant);
}


/**
  * @brief Given a tresholded image, find the contours, calculate their polygonal approximation
  * and take those that accomplish some conditions
  */
static void _findMarkerContours(InputArray _in, vector< vector< Point2f > > &candidates,
                                vector< vector< Point > > &contoursOut, double minPerimeterRate,
                                double maxPerimeterRate, double accuracyRate,
                                double minCornerDistanceRate, int minDistanceToBorder) {

    CV_Assert(minPerimeterRate > 0 && maxPerimeterRate > 0 && accuracyRate > 0 &&
              minCornerDistanceRate >= 0 && minDistanceToBorder >= 0);

    // calculate maximum and minimum sizes in pixels
    unsigned int minPerimeterPixels =
        (unsigned int)(minPerimeterRate * max(_in.getMat().cols, _in.getMat().rows));
    unsigned int maxPerimeterPixels =
        (unsigned int)(maxPerimeterRate * max(_in.getMat().cols, _in.getMat().rows));

    Mat contoursImg;
    _in.getMat().copyTo(contoursImg);
    vector< vector< Point > > contours;
148
    findContours(contoursImg, contours, RETR_LIST, CHAIN_APPROX_NONE);
S. Garrido's avatar
S. Garrido committed
149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212
    // now filter list of contours
    for(unsigned int i = 0; i < contours.size(); i++) {
        // check perimeter
        if(contours[i].size() < minPerimeterPixels || contours[i].size() > maxPerimeterPixels)
            continue;

        // check is square and is convex
        vector< Point > approxCurve;
        approxPolyDP(contours[i], approxCurve, double(contours[i].size()) * accuracyRate, true);
        if(approxCurve.size() != 4 || !isContourConvex(approxCurve)) continue;

        // check min distance between corners
        double minDistSq =
            max(contoursImg.cols, contoursImg.rows) * max(contoursImg.cols, contoursImg.rows);
        for(int j = 0; j < 4; j++) {
            double d = (double)(approxCurve[j].x - approxCurve[(j + 1) % 4].x) *
                           (double)(approxCurve[j].x - approxCurve[(j + 1) % 4].x) +
                       (double)(approxCurve[j].y - approxCurve[(j + 1) % 4].y) *
                           (double)(approxCurve[j].y - approxCurve[(j + 1) % 4].y);
            minDistSq = min(minDistSq, d);
        }
        double minCornerDistancePixels = double(contours[i].size()) * minCornerDistanceRate;
        if(minDistSq < minCornerDistancePixels * minCornerDistancePixels) continue;

        // check if it is too near to the image border
        bool tooNearBorder = false;
        for(int j = 0; j < 4; j++) {
            if(approxCurve[j].x < minDistanceToBorder || approxCurve[j].y < minDistanceToBorder ||
               approxCurve[j].x > contoursImg.cols - 1 - minDistanceToBorder ||
               approxCurve[j].y > contoursImg.rows - 1 - minDistanceToBorder)
                tooNearBorder = true;
        }
        if(tooNearBorder) continue;

        // if it passes all the test, add to candidates vector
        vector< Point2f > currentCandidate;
        currentCandidate.resize(4);
        for(int j = 0; j < 4; j++) {
            currentCandidate[j] = Point2f((float)approxCurve[j].x, (float)approxCurve[j].y);
        }
        candidates.push_back(currentCandidate);
        contoursOut.push_back(contours[i]);
    }
}


/**
  * @brief Assure order of candidate corners is clockwise direction
  */
static void _reorderCandidatesCorners(vector< vector< Point2f > > &candidates) {

    for(unsigned int i = 0; i < candidates.size(); i++) {
        double dx1 = candidates[i][1].x - candidates[i][0].x;
        double dy1 = candidates[i][1].y - candidates[i][0].y;
        double dx2 = candidates[i][2].x - candidates[i][0].x;
        double dy2 = candidates[i][2].y - candidates[i][0].y;
        double crossProduct = (dx1 * dy2) - (dy1 * dx2);

        if(crossProduct < 0.0) { // not clockwise direction
            swap(candidates[i][1], candidates[i][3]);
        }
    }
}

213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228
/**
  * @brief to make sure that the corner's order of both candidates (default/white) is the same
  */
static vector< Point2f > alignContourOrder( Point2f corner, vector< Point2f > candidate){
    uint8_t r=0;
    double min = cv::norm( Vec2f( corner - candidate[0] ), NORM_L2SQR);
    for(uint8_t pos=1; pos < 4; pos++) {
        double nDiff = cv::norm( Vec2f( corner - candidate[pos] ), NORM_L2SQR);
        if(nDiff < min){
            r = pos;
            min =nDiff;
        }
    }
    std::rotate(candidate.begin(), candidate.begin() + r, candidate.end());
    return candidate;
}
S. Garrido's avatar
S. Garrido committed
229 230

/**
231 232
  * @brief Check candidates that are too close to each other, save the potential candidates
  *        (i.e. biggest/smallest contour) and remove the rest
S. Garrido's avatar
S. Garrido committed
233 234
  */
static void _filterTooCloseCandidates(const vector< vector< Point2f > > &candidatesIn,
235
                                      vector< vector< vector< Point2f > > > &candidatesSetOut,
S. Garrido's avatar
S. Garrido committed
236
                                      const vector< vector< Point > > &contoursIn,
237 238
                                      vector< vector< vector< Point > > > &contoursSetOut,
                                      double minMarkerDistanceRate, bool detectInvertedMarker) {
S. Garrido's avatar
S. Garrido committed
239 240 241

    CV_Assert(minMarkerDistanceRate >= 0);

242 243 244
    vector<int> candGroup;
    candGroup.resize(candidatesIn.size(), -1);
    vector< vector<unsigned int> > groupedCandidates;
S. Garrido's avatar
S. Garrido committed
245 246 247 248 249
    for(unsigned int i = 0; i < candidatesIn.size(); i++) {
        for(unsigned int j = i + 1; j < candidatesIn.size(); j++) {

            int minimumPerimeter = min((int)contoursIn[i].size(), (int)contoursIn[j].size() );

folz's avatar
folz committed
250
            // fc is the first corner considered on one of the markers, 4 combinations are possible
S. Garrido's avatar
S. Garrido committed
251 252 253 254 255 256 257 258 259 260 261 262 263 264 265
            for(int fc = 0; fc < 4; fc++) {
                double distSq = 0;
                for(int c = 0; c < 4; c++) {
                    // modC is the corner considering first corner is fc
                    int modC = (c + fc) % 4;
                    distSq += (candidatesIn[i][modC].x - candidatesIn[j][c].x) *
                                  (candidatesIn[i][modC].x - candidatesIn[j][c].x) +
                              (candidatesIn[i][modC].y - candidatesIn[j][c].y) *
                                  (candidatesIn[i][modC].y - candidatesIn[j][c].y);
                }
                distSq /= 4.;

                // if mean square distance is too low, remove the smaller one of the two markers
                double minMarkerDistancePixels = double(minimumPerimeter) * minMarkerDistanceRate;
                if(distSq < minMarkerDistancePixels * minMarkerDistancePixels) {
266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293

                    // i and j are not related to a group
                    if(candGroup[i]<0 && candGroup[j]<0){
                        // mark candidates with their corresponding group number
                        candGroup[i] = candGroup[j] = (int)groupedCandidates.size();

                        // create group
                        vector<unsigned int> grouped;
                        grouped.push_back(i);
                        grouped.push_back(j);
                        groupedCandidates.push_back( grouped );
                    }
                    // i is related to a group
                    else if(candGroup[i] > -1 && candGroup[j] == -1){
                        int group = candGroup[i];
                        candGroup[j] = group;

                        // add to group
                        groupedCandidates[group].push_back( j );
                    }
                    // j is related to a group
                    else if(candGroup[j] > -1 && candGroup[i] == -1){
                        int group = candGroup[j];
                        candGroup[i] = group;

                        // add to group
                        groupedCandidates[group].push_back( i );
                    }
S. Garrido's avatar
S. Garrido committed
294 295 296 297 298
                }
            }
        }
    }

299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331
    // save possible candidates
    candidatesSetOut.clear();
    contoursSetOut.clear();

    vector< vector< Point2f > > biggerCandidates;
    vector< vector< Point > > biggerContours;
    vector< vector< Point2f > > smallerCandidates;
    vector< vector< Point > > smallerContours;

    // save possible candidates
    for( unsigned int i = 0; i < groupedCandidates.size(); i++ ) {
        int smallerIdx = groupedCandidates[i][0];
        int biggerIdx = -1;

        // evaluate group elements
        for( unsigned int j = 1; j < groupedCandidates[i].size(); j++ ) {
            size_t currPerim = contoursIn[ groupedCandidates[i][j] ].size();

            // check if current contour is bigger
            if ( biggerIdx < 0 )
                biggerIdx = groupedCandidates[i][j];
            else if(currPerim >= contoursIn[ biggerIdx ].size())
                biggerIdx = groupedCandidates[i][j];

            // check if current contour is smaller
            if(currPerim < contoursIn[ smallerIdx ].size() && detectInvertedMarker)
                smallerIdx = groupedCandidates[i][j];
        }
        // add contours und candidates
        if(biggerIdx > -1){

            biggerCandidates.push_back(candidatesIn[biggerIdx]);
            biggerContours.push_back(contoursIn[biggerIdx]);
S. Garrido's avatar
S. Garrido committed
332

333
            if( detectInvertedMarker ){
334
                smallerCandidates.push_back(alignContourOrder(candidatesIn[biggerIdx][0], candidatesIn[smallerIdx]));
335 336 337
                smallerContours.push_back(contoursIn[smallerIdx]);
            }
        }
S. Garrido's avatar
S. Garrido committed
338
    }
339 340 341 342 343 344 345
    // to preserve the structure :: candidateSet< defaultCandidates, whiteCandidates >
    // default candidates
    candidatesSetOut.push_back(biggerCandidates);
    contoursSetOut.push_back(biggerContours);
    // white candidates
    candidatesSetOut.push_back(smallerCandidates);
    contoursSetOut.push_back(smallerContours);
S. Garrido's avatar
S. Garrido committed
346 347 348 349 350 351 352 353 354 355 356 357
}


/**
  * ParallelLoopBody class for the parallelization of the basic candidate detections using
  * different threhold window sizes. Called from function _detectInitialCandidates()
  */
class DetectInitialCandidatesParallel : public ParallelLoopBody {
    public:
    DetectInitialCandidatesParallel(const Mat *_grey,
                                    vector< vector< vector< Point2f > > > *_candidatesArrays,
                                    vector< vector< vector< Point > > > *_contoursArrays,
358
                                    const Ptr<DetectorParameters> &_params)
S. Garrido's avatar
S. Garrido committed
359 360 361
        : grey(_grey), candidatesArrays(_candidatesArrays), contoursArrays(_contoursArrays),
          params(_params) {}

362
    void operator()(const Range &range) const CV_OVERRIDE {
S. Garrido's avatar
S. Garrido committed
363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386
        const int begin = range.start;
        const int end = range.end;

        for(int i = begin; i < end; i++) {
            int currScale =
                params->adaptiveThreshWinSizeMin + i * params->adaptiveThreshWinSizeStep;
            // threshold
            Mat thresh;
            _threshold(*grey, thresh, currScale, params->adaptiveThreshConstant);

            // detect rectangles
            _findMarkerContours(thresh, (*candidatesArrays)[i], (*contoursArrays)[i],
                                params->minMarkerPerimeterRate, params->maxMarkerPerimeterRate,
                                params->polygonalApproxAccuracyRate, params->minCornerDistanceRate,
                                params->minDistanceToBorder);
        }
    }

    private:
    DetectInitialCandidatesParallel &operator=(const DetectInitialCandidatesParallel &);

    const Mat *grey;
    vector< vector< vector< Point2f > > > *candidatesArrays;
    vector< vector< vector< Point > > > *contoursArrays;
387
    const Ptr<DetectorParameters> &params;
S. Garrido's avatar
S. Garrido committed
388 389 390 391 392 393 394 395
};


/**
 * @brief Initial steps on finding square candidates
 */
static void _detectInitialCandidates(const Mat &grey, vector< vector< Point2f > > &candidates,
                                     vector< vector< Point > > &contours,
396
                                     const Ptr<DetectorParameters> &params) {
S. Garrido's avatar
S. Garrido committed
397

398 399 400
    CV_Assert(params->adaptiveThreshWinSizeMin >= 3 && params->adaptiveThreshWinSizeMax >= 3);
    CV_Assert(params->adaptiveThreshWinSizeMax >= params->adaptiveThreshWinSizeMin);
    CV_Assert(params->adaptiveThreshWinSizeStep > 0);
S. Garrido's avatar
S. Garrido committed
401 402

    // number of window sizes (scales) to apply adaptive thresholding
403 404
    int nScales =  (params->adaptiveThreshWinSizeMax - params->adaptiveThreshWinSizeMin) /
                      params->adaptiveThreshWinSizeStep + 1;
S. Garrido's avatar
S. Garrido committed
405

folz's avatar
folz committed
406 407
    vector< vector< vector< Point2f > > > candidatesArrays((size_t) nScales);
    vector< vector< vector< Point > > > contoursArrays((size_t) nScales);
408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423

    ////for each value in the interval of thresholding window sizes
    // for(int i = 0; i < nScales; i++) {
    //    int currScale = params.adaptiveThreshWinSizeMin + i*params.adaptiveThreshWinSizeStep;
    //    // treshold
    //    Mat thresh;
    //    _threshold(grey, thresh, currScale, params.adaptiveThreshConstant);
    //    // detect rectangles
    //    _findMarkerContours(thresh, candidatesArrays[i], contoursArrays[i],
    // params.minMarkerPerimeterRate,
    //                        params.maxMarkerPerimeterRate, params.polygonalApproxAccuracyRate,
    //                        params.minCornerDistance, params.minDistanceToBorder);
    //}

    // this is the parallel call for the previous commented loop (result is equivalent)
    parallel_for_(Range(0, nScales), DetectInitialCandidatesParallel(&grey, &candidatesArrays,
424
                                                                     &contoursArrays, params));
425 426 427 428 429 430

    // join candidates
    for(int i = 0; i < nScales; i++) {
        for(unsigned int j = 0; j < candidatesArrays[i].size(); j++) {
            candidates.push_back(candidatesArrays[i][j]);
            contours.push_back(contoursArrays[i][j]);
S. Garrido's avatar
S. Garrido committed
431 432 433 434 435 436 437 438
        }
    }
}


/**
 * @brief Detect square candidates in the input image
 */
439 440
static void _detectCandidates(InputArray _image, vector< vector< vector< Point2f > > >& candidatesSetOut,
                              vector< vector< vector< Point > > >& contoursSetOut, const Ptr<DetectorParameters> &_params) {
S. Garrido's avatar
S. Garrido committed
441 442 443 444 445 446 447 448 449 450 451

    Mat image = _image.getMat();
    CV_Assert(image.total() != 0);

    /// 1. CONVERT TO GRAY
    Mat grey;
    _convertToGrey(image, grey);

    vector< vector< Point2f > > candidates;
    vector< vector< Point > > contours;
    /// 2. DETECT FIRST SET OF CANDIDATES
452
    _detectInitialCandidates(grey, candidates, contours, _params);
S. Garrido's avatar
S. Garrido committed
453 454 455 456 457

    /// 3. SORT CORNERS
    _reorderCandidatesCorners(candidates);

    /// 4. FILTER OUT NEAR CANDIDATE PAIRS
458 459 460
    // save the outter/inner border (i.e. potential candidates)
    _filterTooCloseCandidates(candidates, candidatesSetOut, contours, contoursSetOut,
                              _params->minMarkerDistanceRate, _params->detectInvertedMarker);
S. Garrido's avatar
S. Garrido committed
461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524
}


/**
  * @brief Given an input image and candidate corners, extract the bits of the candidate, including
  * the border bits
  */
static Mat _extractBits(InputArray _image, InputArray _corners, int markerSize,
                        int markerBorderBits, int cellSize, double cellMarginRate,
                        double minStdDevOtsu) {

    CV_Assert(_image.getMat().channels() == 1);
    CV_Assert(_corners.total() == 4);
    CV_Assert(markerBorderBits > 0 && cellSize > 0 && cellMarginRate >= 0 && cellMarginRate <= 1);
    CV_Assert(minStdDevOtsu >= 0);

    // number of bits in the marker
    int markerSizeWithBorders = markerSize + 2 * markerBorderBits;
    int cellMarginPixels = int(cellMarginRate * cellSize);

    Mat resultImg; // marker image after removing perspective
    int resultImgSize = markerSizeWithBorders * cellSize;
    Mat resultImgCorners(4, 1, CV_32FC2);
    resultImgCorners.ptr< Point2f >(0)[0] = Point2f(0, 0);
    resultImgCorners.ptr< Point2f >(0)[1] = Point2f((float)resultImgSize - 1, 0);
    resultImgCorners.ptr< Point2f >(0)[2] =
        Point2f((float)resultImgSize - 1, (float)resultImgSize - 1);
    resultImgCorners.ptr< Point2f >(0)[3] = Point2f(0, (float)resultImgSize - 1);

    // remove perspective
    Mat transformation = getPerspectiveTransform(_corners, resultImgCorners);
    warpPerspective(_image, resultImg, transformation, Size(resultImgSize, resultImgSize),
                    INTER_NEAREST);

    // output image containing the bits
    Mat bits(markerSizeWithBorders, markerSizeWithBorders, CV_8UC1, Scalar::all(0));

    // check if standard deviation is enough to apply Otsu
    // if not enough, it probably means all bits are the same color (black or white)
    Mat mean, stddev;
    // Remove some border just to avoid border noise from perspective transformation
    Mat innerRegion = resultImg.colRange(cellSize / 2, resultImg.cols - cellSize / 2)
                          .rowRange(cellSize / 2, resultImg.rows - cellSize / 2);
    meanStdDev(innerRegion, mean, stddev);
    if(stddev.ptr< double >(0)[0] < minStdDevOtsu) {
        // all black or all white, depending on mean value
        if(mean.ptr< double >(0)[0] > 127)
            bits.setTo(1);
        else
            bits.setTo(0);
        return bits;
    }

    // now extract code, first threshold using Otsu
    threshold(resultImg, resultImg, 125, 255, THRESH_BINARY | THRESH_OTSU);

    // for each cell
    for(int y = 0; y < markerSizeWithBorders; y++) {
        for(int x = 0; x < markerSizeWithBorders; x++) {
            int Xstart = x * (cellSize) + cellMarginPixels;
            int Ystart = y * (cellSize) + cellMarginPixels;
            Mat square = resultImg(Rect(Xstart, Ystart, cellSize - 2 * cellMarginPixels,
                                        cellSize - 2 * cellMarginPixels));
            // count white pixels on each cell to assign its value
folz's avatar
folz committed
525
            size_t nZ = (size_t) countNonZero(square);
S. Garrido's avatar
S. Garrido committed
526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562
            if(nZ > square.total() / 2) bits.at< unsigned char >(y, x) = 1;
        }
    }

    return bits;
}



/**
  * @brief Return number of erroneous bits in border, i.e. number of white bits in border.
  */
static int _getBorderErrors(const Mat &bits, int markerSize, int borderSize) {

    int sizeWithBorders = markerSize + 2 * borderSize;

    CV_Assert(markerSize > 0 && bits.cols == sizeWithBorders && bits.rows == sizeWithBorders);

    int totalErrors = 0;
    for(int y = 0; y < sizeWithBorders; y++) {
        for(int k = 0; k < borderSize; k++) {
            if(bits.ptr< unsigned char >(y)[k] != 0) totalErrors++;
            if(bits.ptr< unsigned char >(y)[sizeWithBorders - 1 - k] != 0) totalErrors++;
        }
    }
    for(int x = borderSize; x < sizeWithBorders - borderSize; x++) {
        for(int k = 0; k < borderSize; k++) {
            if(bits.ptr< unsigned char >(k)[x] != 0) totalErrors++;
            if(bits.ptr< unsigned char >(sizeWithBorders - 1 - k)[x] != 0) totalErrors++;
        }
    }
    return totalErrors;
}


/**
 * @brief Tries to identify one candidate given the dictionary
563 564 565
 * @return candidate typ. zero if the candidate is not valid,
 *                           1 if the candidate is a black candidate (default candidate)
 *                           2 if the candidate is a white candidate
S. Garrido's avatar
S. Garrido committed
566
 */
567
static uint8_t _identifyOneCandidate(const Ptr<Dictionary>& dictionary, InputArray _image,
568
                                  vector<Point2f>& _corners, int& idx,
569
                                  const Ptr<DetectorParameters>& params, int& rotation)
570 571
{
    CV_Assert(_corners.size() == 4);
S. Garrido's avatar
S. Garrido committed
572
    CV_Assert(_image.getMat().total() != 0);
573
    CV_Assert(params->markerBorderBits > 0);
S. Garrido's avatar
S. Garrido committed
574

575
    uint8_t typ=1;
S. Garrido's avatar
S. Garrido committed
576 577
    // get bits
    Mat candidateBits =
578 579 580
        _extractBits(_image, _corners, dictionary->markerSize, params->markerBorderBits,
                     params->perspectiveRemovePixelPerCell,
                     params->perspectiveRemoveIgnoredMarginPerCell, params->minOtsuStdDev);
S. Garrido's avatar
S. Garrido committed
581 582 583

    // analyze border bits
    int maximumErrorsInBorder =
584
        int(dictionary->markerSize * dictionary->markerSize * params->maxErroneousBitsInBorderRate);
S. Garrido's avatar
S. Garrido committed
585
    int borderErrors =
586
        _getBorderErrors(candidateBits, dictionary->markerSize, params->markerBorderBits);
587 588 589 590 591 592 593 594 595 596

    // check if it is a white marker
    if(params->detectInvertedMarker){
        // to get from 255 to 1
        Mat invertedImg = ~candidateBits-254;
        int invBError = _getBorderErrors(invertedImg, dictionary->markerSize, params->markerBorderBits);
        // white marker
        if(invBError<borderErrors){
            borderErrors = invBError;
            invertedImg.copyTo(candidateBits);
597
            typ=2;
598 599
        }
    }
600
    if(borderErrors > maximumErrorsInBorder) return 0; // border is wrong
S. Garrido's avatar
S. Garrido committed
601 602 603

    // take only inner bits
    Mat onlyBits =
604 605 606
        candidateBits.rowRange(params->markerBorderBits,
                               candidateBits.rows - params->markerBorderBits)
            .colRange(params->markerBorderBits, candidateBits.rows - params->markerBorderBits);
S. Garrido's avatar
S. Garrido committed
607 608

    // try to indentify the marker
609
    if(!dictionary->identify(onlyBits, idx, rotation, params->errorCorrectionRate))
610
        return 0;
611

612
    return typ;
S. Garrido's avatar
S. Garrido committed
613 614 615 616 617 618 619 620 621
}


/**
  * ParallelLoopBody class for the parallelization of the marker identification step
  * Called from function _identifyCandidates()
  */
class IdentifyCandidatesParallel : public ParallelLoopBody {
    public:
622 623
    IdentifyCandidatesParallel(const Mat& _grey, vector< vector< Point2f > >& _candidates,
                               const Ptr<Dictionary> &_dictionary,
624
                               vector< int >& _idsTmp, vector< uint8_t >& _validCandidates,
625 626
                               const Ptr<DetectorParameters> &_params,
                               vector< int > &_rotated)
627
        : grey(_grey), candidates(_candidates), dictionary(_dictionary),
628
          idsTmp(_idsTmp), validCandidates(_validCandidates), params(_params), rotated(_rotated) {}
S. Garrido's avatar
S. Garrido committed
629

630 631
    void operator()(const Range &range) const CV_OVERRIDE
    {
S. Garrido's avatar
S. Garrido committed
632 633 634 635 636
        const int begin = range.start;
        const int end = range.end;

        for(int i = begin; i < end; i++) {
            int currId;
637
            validCandidates[i] = _identifyOneCandidate(dictionary, grey, candidates[i], currId, params, rotated[i]);
638 639

            if(validCandidates[i] > 0)
640
                idsTmp[i] = currId;
S. Garrido's avatar
S. Garrido committed
641
        }
642

S. Garrido's avatar
S. Garrido committed
643 644 645 646 647
    }

    private:
    IdentifyCandidatesParallel &operator=(const IdentifyCandidatesParallel &); // to quiet MSVC

648
    const Mat &grey;
649
    vector< vector< Point2f > >& candidates;
650
    const Ptr<Dictionary> &dictionary;
651
    vector< int > &idsTmp;
652
    vector< uint8_t > &validCandidates;
653
    const Ptr<DetectorParameters> &params;
654
    vector< int > &rotated;
S. Garrido's avatar
S. Garrido committed
655 656 657 658
};



659
/**
660
 * @brief Copy the contents of a corners vector to an OutputArray, settings its size.
661
 */
662
static void _copyVector2Output(vector< vector< Point2f > > &vec, OutputArrayOfArrays out) {
663 664 665 666
    out.create((int)vec.size(), 1, CV_32FC2);

    if(out.isMatVector()) {
        for (unsigned int i = 0; i < vec.size(); i++) {
667
            out.create(4, 1, CV_32FC2, i);
668
            Mat &m = out.getMatRef(i);
669
            Mat(Mat(vec[i]).t()).copyTo(m);
670 671 672 673
        }
    }
    else if(out.isUMatVector()) {
        for (unsigned int i = 0; i < vec.size(); i++) {
674
            out.create(4, 1, CV_32FC2, i);
675
            UMat &m = out.getUMatRef(i);
676
            Mat(Mat(vec[i]).t()).copyTo(m);
677 678 679 680
        }
    }
    else if(out.kind() == _OutputArray::STD_VECTOR_VECTOR){
        for (unsigned int i = 0; i < vec.size(); i++) {
681
            out.create(4, 1, CV_32FC2, i);
682
            Mat m = out.getMat(i);
683
            Mat(Mat(vec[i]).t()).copyTo(m);
684 685 686 687 688 689 690 691
        }
    }
    else {
        CV_Error(cv::Error::StsNotImplemented,
                 "Only Mat vector, UMat vector, and vector<vector> OutputArrays are currently supported.");
    }
}

692 693 694 695 696 697
/**
 * @brief rotate the initial corner to get to the right position
 */
static void correctCornerPosition( vector< Point2f >& _candidate, int rotate){
    std::rotate(_candidate.begin(), _candidate.begin() + 4 - rotate, _candidate.end());
}
698

S. Garrido's avatar
S. Garrido committed
699 700 701
/**
 * @brief Identify square candidates according to a marker dictionary
 */
702 703 704
static void _identifyCandidates(InputArray _image, vector< vector< vector< Point2f > > >& _candidatesSet,
                                vector< vector< vector<Point> > >& _contoursSet, const Ptr<Dictionary> &_dictionary,
                                vector< vector< Point2f > >& _accepted, vector< vector<Point> >& _contours, vector< int >& ids,
705
                                const Ptr<DetectorParameters> &params,
S. Garrido's avatar
S. Garrido committed
706 707
                                OutputArrayOfArrays _rejected = noArray()) {

708
    int ncandidates = (int)_candidatesSet[0].size();
709 710
    vector< vector< Point2f > > accepted;
    vector< vector< Point2f > > rejected;
S. Garrido's avatar
S. Garrido committed
711

712 713
    vector< vector< Point > > contours;

S. Garrido's avatar
S. Garrido committed
714 715 716 717 718 719
    CV_Assert(_image.getMat().total() != 0);

    Mat grey;
    _convertToGrey(_image.getMat(), grey);

    vector< int > idsTmp(ncandidates, -1);
720
    vector< int > rotated(ncandidates, 0);
721
    vector< uint8_t > validCandidates(ncandidates, 0);
S. Garrido's avatar
S. Garrido committed
722 723 724

    //// Analyze each of the candidates
    parallel_for_(Range(0, ncandidates),
725 726 727
                  IdentifyCandidatesParallel(grey,
                                             params->detectInvertedMarker ? _candidatesSet[1] : _candidatesSet[0],
                                             _dictionary, idsTmp,
728
                                             validCandidates, params, rotated));
S. Garrido's avatar
S. Garrido committed
729 730

    for(int i = 0; i < ncandidates; i++) {
731
        if(validCandidates[i] > 0) {
732 733
            // to choose the right set of candidates :: 0 for default, 1 for white markers
            uint8_t set = validCandidates[i]-1;
734

735 736 737 738
            // shift corner positions to the correct rotation
            correctCornerPosition(_candidatesSet[set][i], rotated[i]);

            if( !params->detectInvertedMarker && validCandidates[i] == 2 )
739
                continue;
740 741 742

            // add valid candidate
            accepted.push_back(_candidatesSet[set][i]);
S. Garrido's avatar
S. Garrido committed
743
            ids.push_back(idsTmp[i]);
744

745
            contours.push_back(_contoursSet[set][i]);
746

S. Garrido's avatar
S. Garrido committed
747
        } else {
748
            rejected.push_back(_candidatesSet[0][i]);
S. Garrido's avatar
S. Garrido committed
749 750 751 752
        }
    }

    // parse output
753
    _accepted = accepted;
S. Garrido's avatar
S. Garrido committed
754

755 756
    _contours= contours;

S. Garrido's avatar
S. Garrido committed
757
    if(_rejected.needed()) {
758
        _copyVector2Output(rejected, _rejected);
S. Garrido's avatar
S. Garrido committed
759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788
    }
}


/**
  * @brief Return object points for the system centered in a single marker, given the marker length
  */
static void _getSingleMarkerObjectPoints(float markerLength, OutputArray _objPoints) {

    CV_Assert(markerLength > 0);

    _objPoints.create(4, 1, CV_32FC3);
    Mat objPoints = _objPoints.getMat();
    // set coordinate system in the middle of the marker, with Z pointing out
    objPoints.ptr< Vec3f >(0)[0] = Vec3f(-markerLength / 2.f, markerLength / 2.f, 0);
    objPoints.ptr< Vec3f >(0)[1] = Vec3f(markerLength / 2.f, markerLength / 2.f, 0);
    objPoints.ptr< Vec3f >(0)[2] = Vec3f(markerLength / 2.f, -markerLength / 2.f, 0);
    objPoints.ptr< Vec3f >(0)[3] = Vec3f(-markerLength / 2.f, -markerLength / 2.f, 0);
}




/**
  * ParallelLoopBody class for the parallelization of the marker corner subpixel refinement
  * Called from function detectMarkers()
  */
class MarkerSubpixelParallel : public ParallelLoopBody {
    public:
    MarkerSubpixelParallel(const Mat *_grey, OutputArrayOfArrays _corners,
789
                           const Ptr<DetectorParameters> &_params)
S. Garrido's avatar
S. Garrido committed
790 791
        : grey(_grey), corners(_corners), params(_params) {}

792
    void operator()(const Range &range) const CV_OVERRIDE {
S. Garrido's avatar
S. Garrido committed
793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809
        const int begin = range.start;
        const int end = range.end;

        for(int i = begin; i < end; i++) {
            cornerSubPix(*grey, corners.getMat(i),
                         Size(params->cornerRefinementWinSize, params->cornerRefinementWinSize),
                         Size(-1, -1), TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
                                                    params->cornerRefinementMaxIterations,
                                                    params->cornerRefinementMinAccuracy));
        }
    }

    private:
    MarkerSubpixelParallel &operator=(const MarkerSubpixelParallel &); // to quiet MSVC

    const Mat *grey;
    OutputArrayOfArrays corners;
810
    const Ptr<DetectorParameters> &params;
S. Garrido's avatar
S. Garrido committed
811 812
};

813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964
/**
 * Line fitting  A * B = C :: Called from function refineCandidateLines
 * @param nContours, contour-container
 */
static Point3f _interpolate2Dline(const std::vector<cv::Point2f>& nContours){
	float minX, minY, maxX, maxY;
	minX = maxX = nContours[0].x;
	minY = maxY = nContours[0].y;

	for(unsigned int i = 0; i< nContours.size(); i++){
		minX = nContours[i].x < minX ? nContours[i].x : minX;
		minY = nContours[i].y < minY ? nContours[i].y : minY;
		maxX = nContours[i].x > maxX ? nContours[i].x : maxX;
		maxY = nContours[i].y > maxY ? nContours[i].y : maxY;
	}

	Mat A = Mat::ones((int)nContours.size(), 2, CV_32F); // Coefficient Matrix (N x 2)
	Mat B((int)nContours.size(), 1, CV_32F);				// Variables   Matrix (N x 1)
	Mat C;											// Constant

	if(maxX - minX > maxY - minY){
		for(unsigned int i =0; i < nContours.size(); i++){
            A.at<float>(i,0)= nContours[i].x;
            B.at<float>(i,0)= nContours[i].y;
		}

		solve(A, B, C, DECOMP_NORMAL);

		return Point3f(C.at<float>(0, 0), -1., C.at<float>(1, 0));
	}
	else{
		for(unsigned int i =0; i < nContours.size(); i++){
			A.at<float>(i,0)= nContours[i].y;
			B.at<float>(i,0)= nContours[i].x;
		}

		solve(A, B, C, DECOMP_NORMAL);

		return Point3f(-1., C.at<float>(0, 0), C.at<float>(1, 0));
	}

}

/**
 * Find the Point where the lines crosses :: Called from function refineCandidateLines
 * @param nLine1
 * @param nLine2
 * @return Crossed Point
 */
static Point2f _getCrossPoint(Point3f nLine1, Point3f nLine2){
	Matx22f A(nLine1.x, nLine1.y, nLine2.x, nLine2.y);
	Vec2f B(-nLine1.z, -nLine2.z);
	return Vec2f(A.solve(B).val);
}

static void _distortPoints(vector<cv::Point2f>& in, const Mat& camMatrix, const Mat& distCoeff) {
    // trivial extrinsics
    Matx31f Rvec(0,0,0);
    Matx31f Tvec(0,0,0);

    // calculate 3d points and then reproject, so opencv makes the distortion internally
    vector<cv::Point3f> cornersPoints3d;
    for (unsigned int i = 0; i < in.size(); i++){
        float x= (in[i].x - float(camMatrix.at<double>(0, 2))) / float(camMatrix.at<double>(0, 0));
        float y= (in[i].y - float(camMatrix.at<double>(1, 2))) / float(camMatrix.at<double>(1, 1));
        cornersPoints3d.push_back(Point3f(x,y,1));
    }
    cv::projectPoints(cornersPoints3d, Rvec, Tvec, camMatrix, distCoeff, in);
}

/**
 * Refine Corners using the contour vector :: Called from function detectMarkers
 * @param nContours, contour-container
 * @param nCorners, candidate Corners
 * @param camMatrix, cameraMatrix input 3x3 floating-point camera matrix
 * @param distCoeff, distCoeffs vector of distortion coefficient
 */
static void _refineCandidateLines(std::vector<Point>& nContours, std::vector<Point2f>& nCorners, const Mat& camMatrix, const Mat& distCoeff){
	vector<Point2f> contour2f(nContours.begin(), nContours.end());

	if(!camMatrix.empty() && !distCoeff.empty()){
		undistortPoints(contour2f, contour2f, camMatrix, distCoeff);
	}

	/* 5 groups :: to group the edges
	 * 4 - classified by its corner
	 * extra group - (temporary) if contours do not begin with a corner
	 */
	vector<Point2f> cntPts[5];
	int cornerIndex[4]={-1};
	int group=4;

	for ( unsigned int i =0; i < nContours.size(); i++ ) {
		for(unsigned int j=0; j<4; j++){
			if ( nCorners[j] == contour2f[i] ){
				cornerIndex[j] = i;
				group=j;
			}
		}
		cntPts[group].push_back(contour2f[i]);
	}

	// saves extra group into corresponding
	if( !cntPts[4].empty() ){
		for( unsigned int i=0; i < cntPts[4].size() ; i++ )
			cntPts[group].push_back(cntPts[4].at(i));
		cntPts[4].clear();
	}

	//Evaluate contour direction :: using the position of the detected corners
	int inc=1;

        inc = ( (cornerIndex[0] > cornerIndex[1]) &&  (cornerIndex[3] > cornerIndex[0]) ) ? -1:inc;
	inc = ( (cornerIndex[2] > cornerIndex[3]) &&  (cornerIndex[1] > cornerIndex[2]) ) ? -1:inc;

	// calculate the line :: who passes through the grouped points
	Point3f lines[4];
	for(int i=0; i<4; i++){
		lines[i]=_interpolate2Dline(cntPts[i]);
	}

	/*
	 * calculate the corner :: where the lines crosses to each other
	 * clockwise direction		no clockwise direction
	 *      0                           1
	 *      .---. 1                     .---. 2
	 *      |   |                       |   |
	 *    3 .___.                     0 .___.
	 *          2                           3
	 */
	for(int i=0; i < 4; i++){
		if(inc<0)
			nCorners[i] = _getCrossPoint(lines[ i ], lines[ (i+1)%4 ]);	// 01 12 23 30
		else
			nCorners[i] = _getCrossPoint(lines[ i ], lines[ (i+3)%4 ]);	// 30 01 12 23
	}

	if(!camMatrix.empty() && !distCoeff.empty()){
		_distortPoints(nCorners, camMatrix, distCoeff);
	}
}


/**
  * ParallelLoopBody class for the parallelization of the marker corner contour refinement
  * Called from function detectMarkers()
  */
class MarkerContourParallel : public ParallelLoopBody {
    public:
    MarkerContourParallel( vector< vector< Point > >& _contours, vector< vector< Point2f > >& _candidates,  const Mat& _camMatrix, const Mat& _distCoeff)
        : contours(_contours), candidates(_candidates), camMatrix(_camMatrix), distCoeff(_distCoeff){}

965
    void operator()(const Range &range) const CV_OVERRIDE {
966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982

        for(int i = range.start; i < range.end; i++) {
            _refineCandidateLines(contours[i], candidates[i], camMatrix, distCoeff);
        }
    }

    private:
    MarkerContourParallel &operator=(const MarkerContourParallel &){
        return *this;
    }

    vector< vector< Point > >& contours;
    vector< vector< Point2f > >& candidates;
    const Mat& camMatrix;
    const Mat& distCoeff;
};

983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 1082 1083 1084 1085 1086 1087 1088 1089 1090 1091 1092 1093 1094 1095 1096 1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112
#ifdef APRIL_DEBUG
static void _darken(const Mat &im){
    for (int y = 0; y < im.rows; y++) {
        for (int x = 0; x < im.cols; x++) {
            im.data[im.cols*y+x] /= 2;
        }
    }
}
#endif

/**
 *
 * @param im_orig
 * @param _params
 * @param candidates
 * @param contours
 */
static void _apriltag(Mat im_orig, const Ptr<DetectorParameters> & _params, std::vector< std::vector< Point2f > > &candidates,
        std::vector< std::vector< Point > > &contours){

    ///////////////////////////////////////////////////////////
    /// Step 1. Detect quads according to requested image decimation
    /// and blurring parameters.
    Mat quad_im;
    im_orig.copyTo(quad_im);

    if (_params->aprilTagQuadDecimate > 1){
        resize(im_orig, quad_im, Size(), 1/_params->aprilTagQuadDecimate, 1/_params->aprilTagQuadDecimate, INTER_AREA );
    }

    // Apply a Blur
    if (_params->aprilTagQuadSigma != 0) {
        // compute a reasonable kernel width by figuring that the
        // kernel should go out 2 std devs.
        //
        // max sigma          ksz
        // 0.499              1  (disabled)
        // 0.999              3
        // 1.499              5
        // 1.999              7

        float sigma = fabsf((float) _params->aprilTagQuadSigma);

        int ksz = cvFloor(4 * sigma); // 2 std devs in each direction
        ksz |= 1; // make odd number

        if (ksz > 1) {
            if (_params->aprilTagQuadSigma > 0)
                GaussianBlur(quad_im, quad_im, Size(ksz, ksz), sigma, sigma, BORDER_REPLICATE);
            else {
                Mat orig;
                quad_im.copyTo(orig);
                GaussianBlur(quad_im, quad_im, Size(ksz, ksz), sigma, sigma, BORDER_REPLICATE);

                // SHARPEN the image by subtracting the low frequency components.
                for (int y = 0; y < orig.rows; y++) {
                    for (int x = 0; x < orig.cols; x++) {
                        int vorig = orig.data[y*orig.step + x];
                        int vblur = quad_im.data[y*quad_im.step + x];

                        int v = 2*vorig - vblur;
                        if (v < 0)
                            v = 0;
                        if (v > 255)
                            v = 255;

                        quad_im.data[y*quad_im.step + x] = (uint8_t) v;
                    }
                }
            }
        }
    }

#ifdef APRIL_DEBUG
    imwrite("1.1 debug_preprocess.pnm", quad_im);
#endif

    ///////////////////////////////////////////////////////////
    /// Step 2. do the Threshold :: get the set of candidate quads
    zarray_t *quads = apriltag_quad_thresh(_params, quad_im, contours);

    CV_Assert(quads != NULL);

    // adjust centers of pixels so that they correspond to the
    // original full-resolution image.
    if (_params->aprilTagQuadDecimate > 1) {
        for (int i = 0; i < _zarray_size(quads); i++) {
            struct sQuad *q;
            _zarray_get_volatile(quads, i, &q);
            for (int j = 0; j < 4; j++) {
                q->p[j][0] *= _params->aprilTagQuadDecimate;
                q->p[j][1] *= _params->aprilTagQuadDecimate;
            }
        }
    }

#ifdef APRIL_DEBUG
    Mat im_quads = im_orig.clone();
    im_quads = im_quads*0.5;
    srandom(0);

    for (int i = 0; i < _zarray_size(quads); i++) {
        struct sQuad *quad;
        _zarray_get_volatile(quads, i, &quad);

        const int bias = 100;
        int color = bias + (random() % (255-bias));

        line(im_quads, Point(quad->p[0][0], quad->p[0][1]), Point(quad->p[1][0], quad->p[1][1]), color, 1);
        line(im_quads, Point(quad->p[1][0], quad->p[1][1]), Point(quad->p[2][0], quad->p[2][1]), color, 1);
        line(im_quads, Point(quad->p[2][0], quad->p[2][1]), Point(quad->p[3][0], quad->p[3][1]), color, 1);
        line(im_quads, Point(quad->p[3][0], quad->p[3][1]), Point(quad->p[0][0], quad->p[0][1]), color, 1);
    }
    imwrite("1.2 debug_quads_raw.pnm", im_quads);
#endif

    ////////////////////////////////////////////////////////////////
    /// Step 3. Save the output :: candidate corners
    for (int i = 0; i < _zarray_size(quads); i++) {
        struct sQuad *quad;
        _zarray_get_volatile(quads, i, &quad);

        std::vector< Point2f > corners;
        corners.push_back(Point2f(quad->p[3][0], quad->p[3][1]));   //pA
        corners.push_back(Point2f(quad->p[0][0], quad->p[0][1]));   //pB
        corners.push_back(Point2f(quad->p[1][0], quad->p[1][1]));   //pC
        corners.push_back(Point2f(quad->p[2][0], quad->p[2][1]));   //pD

        candidates.push_back(corners);
    }
1113 1114

    _zarray_destroy(quads);
1115
}
S. Garrido's avatar
S. Garrido committed
1116 1117 1118 1119


/**
  */
1120
void detectMarkers(InputArray _image, const Ptr<Dictionary> &_dictionary, OutputArrayOfArrays _corners,
1121
                   OutputArray _ids, const Ptr<DetectorParameters> &_params,
1122
                   OutputArrayOfArrays _rejectedImgPoints, InputArrayOfArrays camMatrix, InputArrayOfArrays distCoeff) {
S. Garrido's avatar
S. Garrido committed
1123

1124
    CV_Assert(!_image.empty());
S. Garrido's avatar
S. Garrido committed
1125 1126 1127 1128 1129 1130 1131

    Mat grey;
    _convertToGrey(_image.getMat(), grey);

    /// STEP 1: Detect marker candidates
    vector< vector< Point2f > > candidates;
    vector< vector< Point > > contours;
1132
    vector< int > ids;
1133

1134 1135
    vector< vector< vector< Point2f > > > candidatesSet;
    vector< vector< vector< Point > > > contoursSet;
1136
    /// STEP 1.a Detect marker candidates :: using AprilTag
1137
    if(_params->cornerRefinementMethod == CORNER_REFINE_APRILTAG){
1138 1139
        _apriltag(grey, _params, candidates, contours);

1140 1141 1142 1143
        candidatesSet.push_back(candidates);
        contoursSet.push_back(contours);
    }

1144 1145
    /// STEP 1.b Detect marker candidates :: traditional way
    else
1146
        _detectCandidates(grey, candidatesSet, contoursSet, _params);
S. Garrido's avatar
S. Garrido committed
1147 1148

    /// STEP 2: Check candidate codification (identify markers)
1149
    _identifyCandidates(grey, candidatesSet, contoursSet, _dictionary, candidates, contours, ids, _params,
S. Garrido's avatar
S. Garrido committed
1150 1151
                        _rejectedImgPoints);

1152 1153 1154
    // copy to output arrays
    _copyVector2Output(candidates, _corners);
    Mat(ids).copyTo(_ids);
S. Garrido's avatar
S. Garrido committed
1155

1156
    /// STEP 3: Corner refinement :: use corner subpix
1157
    if( _params->cornerRefinementMethod == CORNER_REFINE_SUBPIX ) {
1158 1159
        CV_Assert(_params->cornerRefinementWinSize > 0 && _params->cornerRefinementMaxIterations > 0 &&
                  _params->cornerRefinementMinAccuracy > 0);
S. Garrido's avatar
S. Garrido committed
1160 1161

        //// do corner refinement for each of the detected markers
1162
        // for (unsigned int i = 0; i < _corners.cols(); i++) {
S. Garrido's avatar
S. Garrido committed
1163 1164 1165 1166 1167 1168 1169 1170
        //    cornerSubPix(grey, _corners.getMat(i),
        //                 Size(params.cornerRefinementWinSize, params.cornerRefinementWinSize),
        //                 Size(-1, -1), TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
        //                                            params.cornerRefinementMaxIterations,
        //                                            params.cornerRefinementMinAccuracy));
        //}

        // this is the parallel call for the previous commented loop (result is equivalent)
1171
        parallel_for_(Range(0, _corners.cols()),
1172
                      MarkerSubpixelParallel(&grey, _corners, _params));
S. Garrido's avatar
S. Garrido committed
1173
    }
1174

1175
    /// STEP 3, Optional : Corner refinement :: use contour container
1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186
    if( _params->cornerRefinementMethod == CORNER_REFINE_CONTOUR){

        if(! _ids.empty()){

            // do corner refinement using the contours for each detected markers
            parallel_for_(Range(0, _corners.cols()), MarkerContourParallel(contours, candidates, camMatrix.getMat(), distCoeff.getMat()));

            // copy the corners to the output array
            _copyVector2Output(candidates, _corners);
        }
    }
S. Garrido's avatar
S. Garrido committed
1187 1188 1189 1190 1191 1192 1193 1194 1195 1196
}



/**
  * ParallelLoopBody class for the parallelization of the single markers pose estimation
  * Called from function estimatePoseSingleMarkers()
  */
class SinglePoseEstimationParallel : public ParallelLoopBody {
    public:
1197
    SinglePoseEstimationParallel(Mat& _markerObjPoints, InputArrayOfArrays _corners,
S. Garrido's avatar
S. Garrido committed
1198
                                 InputArray _cameraMatrix, InputArray _distCoeffs,
1199
                                 Mat& _rvecs, Mat& _tvecs)
S. Garrido's avatar
S. Garrido committed
1200 1201 1202
        : markerObjPoints(_markerObjPoints), corners(_corners), cameraMatrix(_cameraMatrix),
          distCoeffs(_distCoeffs), rvecs(_rvecs), tvecs(_tvecs) {}

1203
    void operator()(const Range &range) const CV_OVERRIDE {
S. Garrido's avatar
S. Garrido committed
1204 1205 1206 1207
        const int begin = range.start;
        const int end = range.end;

        for(int i = begin; i < end; i++) {
1208
            solvePnP(markerObjPoints, corners.getMat(i), cameraMatrix, distCoeffs,
1209
                    rvecs.at<Vec3d>(i), tvecs.at<Vec3d>(i));
S. Garrido's avatar
S. Garrido committed
1210 1211 1212 1213 1214 1215
        }
    }

    private:
    SinglePoseEstimationParallel &operator=(const SinglePoseEstimationParallel &); // to quiet MSVC

1216
    Mat& markerObjPoints;
S. Garrido's avatar
S. Garrido committed
1217 1218
    InputArrayOfArrays corners;
    InputArray cameraMatrix, distCoeffs;
1219
    Mat& rvecs, tvecs;
S. Garrido's avatar
S. Garrido committed
1220 1221 1222 1223 1224 1225 1226 1227 1228
};




/**
  */
void estimatePoseSingleMarkers(InputArrayOfArrays _corners, float markerLength,
                               InputArray _cameraMatrix, InputArray _distCoeffs,
1229
                               OutputArray _rvecs, OutputArray _tvecs, OutputArray _objPoints) {
S. Garrido's avatar
S. Garrido committed
1230 1231 1232 1233 1234 1235

    CV_Assert(markerLength > 0);

    Mat markerObjPoints;
    _getSingleMarkerObjectPoints(markerLength, markerObjPoints);
    int nMarkers = (int)_corners.total();
1236 1237
    _rvecs.create(nMarkers, 1, CV_64FC3);
    _tvecs.create(nMarkers, 1, CV_64FC3);
S. Garrido's avatar
S. Garrido committed
1238

1239
    Mat rvecs = _rvecs.getMat(), tvecs = _tvecs.getMat();
S. Garrido's avatar
S. Garrido committed
1240 1241 1242 1243 1244 1245 1246 1247 1248

    //// for each marker, calculate its pose
    // for (int i = 0; i < nMarkers; i++) {
    //    solvePnP(markerObjPoints, _corners.getMat(i), _cameraMatrix, _distCoeffs,
    //             _rvecs.getMat(i), _tvecs.getMat(i));
    //}

    // this is the parallel call for the previous commented loop (result is equivalent)
    parallel_for_(Range(0, nMarkers),
1249 1250
                  SinglePoseEstimationParallel(markerObjPoints, _corners, _cameraMatrix,
                                               _distCoeffs, rvecs, tvecs));
1251 1252 1253
    if(_objPoints.needed()){
        markerObjPoints.convertTo(_objPoints, -1);
    }
S. Garrido's avatar
S. Garrido committed
1254 1255 1256 1257
}



1258 1259
void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners,
    InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints) {
S. Garrido's avatar
S. Garrido committed
1260

1261 1262
    CV_Assert(board->ids.size() == board->objPoints.size());
    CV_Assert(detectedIds.total() == detectedCorners.total());
S. Garrido's avatar
S. Garrido committed
1263

1264
    size_t nDetectedMarkers = detectedIds.total();
S. Garrido's avatar
S. Garrido committed
1265 1266 1267 1268 1269 1270 1271 1272

    vector< Point3f > objPnts;
    objPnts.reserve(nDetectedMarkers);

    vector< Point2f > imgPnts;
    imgPnts.reserve(nDetectedMarkers);

    // look for detected markers that belong to the board and get their information
folz's avatar
folz committed
1273
    for(unsigned int i = 0; i < nDetectedMarkers; i++) {
1274 1275 1276
        int currentId = detectedIds.getMat().ptr< int >(0)[i];
        for(unsigned int j = 0; j < board->ids.size(); j++) {
            if(currentId == board->ids[j]) {
S. Garrido's avatar
S. Garrido committed
1277
                for(int p = 0; p < 4; p++) {
1278 1279
                    objPnts.push_back(board->objPoints[j][p]);
                    imgPnts.push_back(detectedCorners.getMat(i).ptr< Point2f >(0)[p]);
S. Garrido's avatar
S. Garrido committed
1280 1281 1282 1283 1284 1285
                }
            }
        }
    }

    // create output
1286 1287
    Mat(objPnts).copyTo(objPoints);
    Mat(imgPnts).copyTo(imgPoints);
S. Garrido's avatar
S. Garrido committed
1288 1289 1290 1291 1292 1293 1294
}



/**
  * Project board markers that are not included in the list of detected markers
  */
1295
static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArrayOfArrays _detectedCorners,
S. Garrido's avatar
S. Garrido committed
1296 1297
                                      InputOutputArray _detectedIds, InputArray _cameraMatrix,
                                      InputArray _distCoeffs,
1298
                                      vector< vector< Point2f > >& _undetectedMarkersProjectedCorners,
S. Garrido's avatar
S. Garrido committed
1299 1300 1301 1302 1303
                                      OutputArray _undetectedMarkersIds) {

    // first estimate board pose with the current avaible markers
    Mat rvec, tvec;
    int boardDetectedMarkers;
1304
    boardDetectedMarkers = aruco::estimatePoseBoard(_detectedCorners, _detectedIds, _board,
S. Garrido's avatar
S. Garrido committed
1305 1306 1307 1308 1309 1310 1311 1312
                                                    _cameraMatrix, _distCoeffs, rvec, tvec);

    // at least one marker from board so rvec and tvec are valid
    if(boardDetectedMarkers == 0) return;

    // search undetected markers and project them using the previous pose
    vector< vector< Point2f > > undetectedCorners;
    vector< int > undetectedIds;
1313
    for(unsigned int i = 0; i < _board->ids.size(); i++) {
S. Garrido's avatar
S. Garrido committed
1314 1315
        int foundIdx = -1;
        for(unsigned int j = 0; j < _detectedIds.total(); j++) {
1316
            if(_board->ids[i] == _detectedIds.getMat().ptr< int >()[j]) {
S. Garrido's avatar
S. Garrido committed
1317 1318 1319 1320 1321 1322 1323 1324
                foundIdx = j;
                break;
            }
        }

        // not detected
        if(foundIdx == -1) {
            undetectedCorners.push_back(vector< Point2f >());
1325 1326
            undetectedIds.push_back(_board->ids[i]);
            projectPoints(_board->objPoints[i], rvec, tvec, _cameraMatrix, _distCoeffs,
S. Garrido's avatar
S. Garrido committed
1327 1328 1329 1330 1331 1332
                          undetectedCorners.back());
        }
    }


    // parse output
1333 1334
    Mat(undetectedIds).copyTo(_undetectedMarkersIds);
    _undetectedMarkersProjectedCorners = undetectedCorners;
S. Garrido's avatar
S. Garrido committed
1335 1336 1337 1338 1339 1340 1341 1342
}



/**
  * Interpolate board markers that are not included in the list of detected markers using
  * global homography
  */
1343
static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArrayOfArrays _detectedCorners,
S. Garrido's avatar
S. Garrido committed
1344
                                      InputOutputArray _detectedIds,
1345
                                      vector< vector< Point2f > >& _undetectedMarkersProjectedCorners,
S. Garrido's avatar
S. Garrido committed
1346 1347 1348 1349
                                      OutputArray _undetectedMarkersIds) {


    // check board points are in the same plane, if not, global homography cannot be applied
1350 1351 1352 1353 1354 1355
    CV_Assert(_board->objPoints.size() > 0);
    CV_Assert(_board->objPoints[0].size() > 0);
    float boardZ = _board->objPoints[0][0].z;
    for(unsigned int i = 0; i < _board->objPoints.size(); i++) {
        for(unsigned int j = 0; j < _board->objPoints[i].size(); j++) {
            CV_Assert(boardZ == _board->objPoints[i][j].z);
S. Garrido's avatar
S. Garrido committed
1356 1357 1358 1359 1360 1361 1362 1363 1364 1365
        }
    }

    vector< Point2f > detectedMarkersObj2DAll; // Object coordinates (without Z) of all the detected
                                               // marker corners in a single vector
    vector< Point2f > imageCornersAll; // Image corners of all detected markers in a single vector
    vector< vector< Point2f > > undetectedMarkersObj2D; // Object coordinates (without Z) of all
                                                        // missing markers in different vectors
    vector< int > undetectedMarkersIds; // ids of missing markers
    // find markers included in board, and missing markers from board. Fill the previous vectors
1366
    for(unsigned int j = 0; j < _board->ids.size(); j++) {
S. Garrido's avatar
S. Garrido committed
1367 1368
        bool found = false;
        for(unsigned int i = 0; i < _detectedIds.total(); i++) {
1369
            if(_detectedIds.getMat().ptr< int >()[i] == _board->ids[j]) {
S. Garrido's avatar
S. Garrido committed
1370 1371 1372
                for(int c = 0; c < 4; c++) {
                    imageCornersAll.push_back(_detectedCorners.getMat(i).ptr< Point2f >()[c]);
                    detectedMarkersObj2DAll.push_back(
1373
                        Point2f(_board->objPoints[j][c].x, _board->objPoints[j][c].y));
S. Garrido's avatar
S. Garrido committed
1374 1375 1376 1377 1378 1379 1380 1381 1382
                }
                found = true;
                break;
            }
        }
        if(!found) {
            undetectedMarkersObj2D.push_back(vector< Point2f >());
            for(int c = 0; c < 4; c++) {
                undetectedMarkersObj2D.back().push_back(
1383
                    Point2f(_board->objPoints[j][c].x, _board->objPoints[j][c].y));
S. Garrido's avatar
S. Garrido committed
1384
            }
1385
            undetectedMarkersIds.push_back(_board->ids[j]);
S. Garrido's avatar
S. Garrido committed
1386 1387 1388 1389 1390 1391 1392
        }
    }
    if(imageCornersAll.size() == 0) return;

    // get homography from detected markers
    Mat transformation = findHomography(detectedMarkersObj2DAll, imageCornersAll);

1393
    _undetectedMarkersProjectedCorners.resize(undetectedMarkersIds.size());
S. Garrido's avatar
S. Garrido committed
1394 1395 1396

    // for each undetected marker, apply transformation
    for(unsigned int i = 0; i < undetectedMarkersObj2D.size(); i++) {
1397
        perspectiveTransform(undetectedMarkersObj2D[i], _undetectedMarkersProjectedCorners[i], transformation);
S. Garrido's avatar
S. Garrido committed
1398 1399
    }

1400
    Mat(undetectedMarkersIds).copyTo(_undetectedMarkersIds);
S. Garrido's avatar
S. Garrido committed
1401 1402 1403 1404 1405 1406
}



/**
  */
1407
void refineDetectedMarkers(InputArray _image, const Ptr<Board> &_board,
S. Garrido's avatar
S. Garrido committed
1408
                           InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds,
1409
                           InputOutputArrayOfArrays _rejectedCorners, InputArray _cameraMatrix,
S. Garrido's avatar
S. Garrido committed
1410 1411
                           InputArray _distCoeffs, float minRepDistance, float errorCorrectionRate,
                           bool checkAllOrders, OutputArray _recoveredIdxs,
1412
                           const Ptr<DetectorParameters> &_params) {
S. Garrido's avatar
S. Garrido committed
1413 1414 1415 1416 1417

    CV_Assert(minRepDistance > 0);

    if(_detectedIds.total() == 0 || _rejectedCorners.total() == 0) return;

1418 1419
    DetectorParameters &params = *_params;

S. Garrido's avatar
S. Garrido committed
1420 1421 1422 1423 1424
    // get projections of missing markers in the board
    vector< vector< Point2f > > undetectedMarkersCorners;
    vector< int > undetectedMarkersIds;
    if(_cameraMatrix.total() != 0) {
        // reproject based on camera projection model
1425
        _projectUndetectedMarkers(_board, _detectedCorners, _detectedIds, _cameraMatrix, _distCoeffs,
S. Garrido's avatar
S. Garrido committed
1426 1427 1428 1429
                                  undetectedMarkersCorners, undetectedMarkersIds);

    } else {
        // reproject based on global homography
1430
        _projectUndetectedMarkers(_board, _detectedCorners, _detectedIds, undetectedMarkersCorners,
S. Garrido's avatar
S. Garrido committed
1431 1432 1433 1434 1435 1436 1437
                                  undetectedMarkersIds);
    }

    // list of missing markers indicating if they have been assigned to a candidate
    vector< bool > alreadyIdentified(_rejectedCorners.total(), false);

    // maximum bits that can be corrected
1438
    Dictionary &dictionary = *(_board->dictionary);
S. Garrido's avatar
S. Garrido committed
1439
    int maxCorrectionRecalculated =
1440
        int(double(dictionary.maxCorrectionBits) * errorCorrectionRate);
S. Garrido's avatar
S. Garrido committed
1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507

    Mat grey;
    _convertToGrey(_image, grey);

    // vector of final detected marker corners and ids
    vector< Mat > finalAcceptedCorners;
    vector< int > finalAcceptedIds;
    // fill with the current markers
    finalAcceptedCorners.resize(_detectedCorners.total());
    finalAcceptedIds.resize(_detectedIds.total());
    for(unsigned int i = 0; i < _detectedIds.total(); i++) {
        finalAcceptedCorners[i] = _detectedCorners.getMat(i).clone();
        finalAcceptedIds[i] = _detectedIds.getMat().ptr< int >()[i];
    }
    vector< int > recoveredIdxs; // original indexes of accepted markers in _rejectedCorners

    // for each missing marker, try to find a correspondence
    for(unsigned int i = 0; i < undetectedMarkersIds.size(); i++) {

        // best match at the moment
        int closestCandidateIdx = -1;
        double closestCandidateDistance = minRepDistance * minRepDistance + 1;
        Mat closestRotatedMarker;

        for(unsigned int j = 0; j < _rejectedCorners.total(); j++) {
            if(alreadyIdentified[j]) continue;

            // check distance
            double minDistance = closestCandidateDistance + 1;
            bool valid = false;
            int validRot = 0;
            for(int c = 0; c < 4; c++) { // first corner in rejected candidate
                double currentMaxDistance = 0;
                for(int k = 0; k < 4; k++) {
                    Point2f rejCorner = _rejectedCorners.getMat(j).ptr< Point2f >()[(c + k) % 4];
                    Point2f distVector = undetectedMarkersCorners[i][k] - rejCorner;
                    double cornerDist = distVector.x * distVector.x + distVector.y * distVector.y;
                    currentMaxDistance = max(currentMaxDistance, cornerDist);
                }
                // if distance is better than current best distance
                if(currentMaxDistance < closestCandidateDistance) {
                    valid = true;
                    validRot = c;
                    minDistance = currentMaxDistance;
                }
                if(!checkAllOrders) break;
            }

            if(!valid) continue;

            // apply rotation
            Mat rotatedMarker;
            if(checkAllOrders) {
                rotatedMarker = Mat(4, 1, CV_32FC2);
                for(int c = 0; c < 4; c++)
                    rotatedMarker.ptr< Point2f >()[c] =
                        _rejectedCorners.getMat(j).ptr< Point2f >()[(c + 4 + validRot) % 4];
            }
            else rotatedMarker = _rejectedCorners.getMat(j);

            // last filter, check if inner code is close enough to the assigned marker code
            int codeDistance = 0;
            // if errorCorrectionRate, dont check code
            if(errorCorrectionRate >= 0) {

                // extract bits
                Mat bits = _extractBits(
1508
                    grey, rotatedMarker, dictionary.markerSize, params.markerBorderBits,
S. Garrido's avatar
S. Garrido committed
1509 1510 1511 1512 1513 1514 1515 1516
                    params.perspectiveRemovePixelPerCell,
                    params.perspectiveRemoveIgnoredMarginPerCell, params.minOtsuStdDev);

                Mat onlyBits =
                    bits.rowRange(params.markerBorderBits, bits.rows - params.markerBorderBits)
                        .colRange(params.markerBorderBits, bits.rows - params.markerBorderBits);

                codeDistance =
1517
                    dictionary.getDistanceToId(onlyBits, undetectedMarkersIds[i], false);
S. Garrido's avatar
S. Garrido committed
1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531
            }

            // if everythin is ok, assign values to current best match
            if(errorCorrectionRate < 0 || codeDistance < maxCorrectionRecalculated) {
                closestCandidateIdx = j;
                closestCandidateDistance = minDistance;
                closestRotatedMarker = rotatedMarker;
            }
        }

        // if at least one good match, we have rescue the missing marker
        if(closestCandidateIdx >= 0) {

            // subpixel refinement
1532
            if(_params->cornerRefinementMethod == CORNER_REFINE_SUBPIX) {
S. Garrido's avatar
S. Garrido committed
1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560
                CV_Assert(params.cornerRefinementWinSize > 0 &&
                          params.cornerRefinementMaxIterations > 0 &&
                          params.cornerRefinementMinAccuracy > 0);
                cornerSubPix(grey, closestRotatedMarker,
                             Size(params.cornerRefinementWinSize, params.cornerRefinementWinSize),
                             Size(-1, -1), TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
                                                        params.cornerRefinementMaxIterations,
                                                        params.cornerRefinementMinAccuracy));
            }

            // remove from rejected
            alreadyIdentified[closestCandidateIdx] = true;

            // add to detected
            finalAcceptedCorners.push_back(closestRotatedMarker);
            finalAcceptedIds.push_back(undetectedMarkersIds[i]);

            // add the original index of the candidate
            recoveredIdxs.push_back(closestCandidateIdx);
        }
    }

    // parse output
    if(finalAcceptedIds.size() != _detectedIds.total()) {
        _detectedCorners.clear();
        _detectedIds.clear();

        // parse output
1561
        Mat(finalAcceptedIds).copyTo(_detectedIds);
S. Garrido's avatar
S. Garrido committed
1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590

        _detectedCorners.create((int)finalAcceptedCorners.size(), 1, CV_32FC2);
        for(unsigned int i = 0; i < finalAcceptedCorners.size(); i++) {
            _detectedCorners.create(4, 1, CV_32FC2, i, true);
            for(int j = 0; j < 4; j++) {
                _detectedCorners.getMat(i).ptr< Point2f >()[j] =
                    finalAcceptedCorners[i].ptr< Point2f >()[j];
            }
        }

        // recalculate _rejectedCorners based on alreadyIdentified
        vector< Mat > finalRejected;
        for(unsigned int i = 0; i < alreadyIdentified.size(); i++) {
            if(!alreadyIdentified[i]) {
                finalRejected.push_back(_rejectedCorners.getMat(i).clone());
            }
        }

        _rejectedCorners.clear();
        _rejectedCorners.create((int)finalRejected.size(), 1, CV_32FC2);
        for(unsigned int i = 0; i < finalRejected.size(); i++) {
            _rejectedCorners.create(4, 1, CV_32FC2, i, true);
            for(int j = 0; j < 4; j++) {
                _rejectedCorners.getMat(i).ptr< Point2f >()[j] =
                    finalRejected[i].ptr< Point2f >()[j];
            }
        }

        if(_recoveredIdxs.needed()) {
1591
            Mat(recoveredIdxs).copyTo(_recoveredIdxs);
S. Garrido's avatar
S. Garrido committed
1592 1593 1594 1595 1596 1597 1598 1599 1600
        }
    }
}




/**
  */
1601
int estimatePoseBoard(InputArrayOfArrays _corners, InputArray _ids, const Ptr<Board> &board,
S. Garrido's avatar
S. Garrido committed
1602
                      InputArray _cameraMatrix, InputArray _distCoeffs, OutputArray _rvec,
1603
                      OutputArray _tvec, bool useExtrinsicGuess) {
S. Garrido's avatar
S. Garrido committed
1604 1605 1606 1607 1608

    CV_Assert(_corners.total() == _ids.total());

    // get object and image points for the solvePnP function
    Mat objPoints, imgPoints;
1609
    getBoardObjectAndImagePoints(board, _corners, _ids, objPoints, imgPoints);
S. Garrido's avatar
S. Garrido committed
1610 1611 1612 1613 1614 1615

    CV_Assert(imgPoints.total() == objPoints.total());

    if(objPoints.total() == 0) // 0 of the detected markers in board
        return 0;

1616
    solvePnP(objPoints, imgPoints, _cameraMatrix, _distCoeffs, _rvec, _tvec, useExtrinsicGuess);
S. Garrido's avatar
S. Garrido committed
1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627

    // divide by four since all the four corners are concatenated in the array for each marker
    return (int)objPoints.total() / 4;
}




/**
 */
void GridBoard::draw(Size outSize, OutputArray _img, int marginSize, int borderBits) {
1628
    _drawPlanarBoardImpl(this, outSize, _img, marginSize, borderBits);
S. Garrido's avatar
S. Garrido committed
1629 1630 1631
}


1632 1633
/**
*/
1634
Ptr<Board> Board::create(InputArrayOfArrays objPoints, const Ptr<Dictionary> &dictionary, InputArray ids) {
1635 1636

    CV_Assert(objPoints.total() == ids.total());
1637
    CV_Assert(objPoints.type() == CV_32FC3 || objPoints.type() == CV_32FC1);
1638 1639 1640 1641 1642

    std::vector< std::vector< Point3f > > obj_points_vector;
    for (unsigned int i = 0; i < objPoints.total(); i++) {
        std::vector<Point3f> corners;
        Mat corners_mat = objPoints.getMat(i);
1643 1644 1645 1646 1647

        if(corners_mat.type() == CV_32FC1)
            corners_mat = corners_mat.reshape(3);
        CV_Assert(corners_mat.total() == 4);

1648 1649 1650 1651 1652 1653 1654 1655 1656
        for (int j = 0; j < 4; j++) {
            corners.push_back(corners_mat.at<Point3f>(j));
        }
        obj_points_vector.push_back(corners);
    }

    Ptr<Board> res = makePtr<Board>();
    ids.copyTo(res->ids);
    res->objPoints = obj_points_vector;
1657
    res->dictionary = cv::makePtr<Dictionary>(dictionary);
1658 1659 1660
    return res;
}

S. Garrido's avatar
S. Garrido committed
1661 1662
/**
 */
1663
Ptr<GridBoard> GridBoard::create(int markersX, int markersY, float markerLength, float markerSeparation,
1664
                            const Ptr<Dictionary> &dictionary, int firstMarker) {
S. Garrido's avatar
S. Garrido committed
1665 1666 1667

    CV_Assert(markersX > 0 && markersY > 0 && markerLength > 0 && markerSeparation > 0);

1668 1669 1670 1671 1672 1673 1674
    Ptr<GridBoard> res = makePtr<GridBoard>();

    res->_markersX = markersX;
    res->_markersY = markersY;
    res->_markerLength = markerLength;
    res->_markerSeparation = markerSeparation;
    res->dictionary = dictionary;
S. Garrido's avatar
S. Garrido committed
1675

folz's avatar
folz committed
1676
    size_t totalMarkers = (size_t) markersX * markersY;
1677 1678
    res->ids.resize(totalMarkers);
    res->objPoints.reserve(totalMarkers);
S. Garrido's avatar
S. Garrido committed
1679 1680

    // fill ids with first identifiers
folz's avatar
folz committed
1681
    for(unsigned int i = 0; i < totalMarkers; i++) {
1682
        res->ids[i] = i + firstMarker;
folz's avatar
folz committed
1683
    }
S. Garrido's avatar
S. Garrido committed
1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695

    // calculate Board objPoints
    float maxY = (float)markersY * markerLength + (markersY - 1) * markerSeparation;
    for(int y = 0; y < markersY; y++) {
        for(int x = 0; x < markersX; x++) {
            vector< Point3f > corners;
            corners.resize(4);
            corners[0] = Point3f(x * (markerLength + markerSeparation),
                                 maxY - y * (markerLength + markerSeparation), 0);
            corners[1] = corners[0] + Point3f(markerLength, 0, 0);
            corners[2] = corners[0] + Point3f(markerLength, -markerLength, 0);
            corners[3] = corners[0] + Point3f(0, -markerLength, 0);
1696
            res->objPoints.push_back(corners);
S. Garrido's avatar
S. Garrido committed
1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753
        }
    }

    return res;
}



/**
 */
void drawDetectedMarkers(InputOutputArray _image, InputArrayOfArrays _corners,
                         InputArray _ids, Scalar borderColor) {


    CV_Assert(_image.getMat().total() != 0 &&
              (_image.getMat().channels() == 1 || _image.getMat().channels() == 3));
    CV_Assert((_corners.total() == _ids.total()) || _ids.total() == 0);

    // calculate colors
    Scalar textColor, cornerColor;
    textColor = cornerColor = borderColor;
    swap(textColor.val[0], textColor.val[1]);     // text color just sawp G and R
    swap(cornerColor.val[1], cornerColor.val[2]); // corner color just sawp G and B

    int nMarkers = (int)_corners.total();
    for(int i = 0; i < nMarkers; i++) {
        Mat currentMarker = _corners.getMat(i);
        CV_Assert(currentMarker.total() == 4 && currentMarker.type() == CV_32FC2);

        // draw marker sides
        for(int j = 0; j < 4; j++) {
            Point2f p0, p1;
            p0 = currentMarker.ptr< Point2f >(0)[j];
            p1 = currentMarker.ptr< Point2f >(0)[(j + 1) % 4];
            line(_image, p0, p1, borderColor, 1);
        }
        // draw first corner mark
        rectangle(_image, currentMarker.ptr< Point2f >(0)[0] - Point2f(3, 3),
                  currentMarker.ptr< Point2f >(0)[0] + Point2f(3, 3), cornerColor, 1, LINE_AA);

        // draw ID
        if(_ids.total() != 0) {
            Point2f cent(0, 0);
            for(int p = 0; p < 4; p++)
                cent += currentMarker.ptr< Point2f >(0)[p];
            cent = cent / 4.;
            stringstream s;
            s << "id=" << _ids.getMat().ptr< int >(0)[i];
            putText(_image, s.str(), cent, FONT_HERSHEY_SIMPLEX, 0.5, textColor, 2);
        }
    }
}



/**
 */
1754 1755 1756 1757
void drawAxis(InputOutputArray _image, InputArray _cameraMatrix, InputArray _distCoeffs, InputArray _rvec,
              InputArray _tvec, float length)
{
    drawFrameAxes(_image, _cameraMatrix, _distCoeffs, _rvec, _tvec, length, 3);
S. Garrido's avatar
S. Garrido committed
1758 1759 1760 1761
}

/**
 */
1762
void drawMarker(const Ptr<Dictionary> &dictionary, int id, int sidePixels, OutputArray _img, int borderBits) {
1763
    dictionary->drawMarker(id, sidePixels, _img, borderBits);
S. Garrido's avatar
S. Garrido committed
1764 1765 1766 1767
}



1768
void _drawPlanarBoardImpl(Board *_board, Size outSize, OutputArray _img, int marginSize,
S. Garrido's avatar
S. Garrido committed
1769 1770
                     int borderBits) {

1771
    CV_Assert(!outSize.empty());
S. Garrido's avatar
S. Garrido committed
1772 1773 1774 1775 1776
    CV_Assert(marginSize >= 0);

    _img.create(outSize, CV_8UC1);
    Mat out = _img.getMat();
    out.setTo(Scalar::all(255));
1777
    out.adjustROI(-marginSize, -marginSize, -marginSize, -marginSize);
S. Garrido's avatar
S. Garrido committed
1778 1779

    // calculate max and min values in XY plane
1780
    CV_Assert(_board->objPoints.size() > 0);
S. Garrido's avatar
S. Garrido committed
1781
    float minX, maxX, minY, maxY;
1782 1783
    minX = maxX = _board->objPoints[0][0].x;
    minY = maxY = _board->objPoints[0][0].y;
S. Garrido's avatar
S. Garrido committed
1784

1785
    for(unsigned int i = 0; i < _board->objPoints.size(); i++) {
S. Garrido's avatar
S. Garrido committed
1786
        for(int j = 0; j < 4; j++) {
1787 1788 1789 1790
            minX = min(minX, _board->objPoints[i][j].x);
            maxX = max(maxX, _board->objPoints[i][j].x);
            minY = min(minY, _board->objPoints[i][j].y);
            maxY = max(maxY, _board->objPoints[i][j].y);
S. Garrido's avatar
S. Garrido committed
1791 1792 1793
        }
    }

1794 1795
    float sizeX = maxX - minX;
    float sizeY = maxY - minY;
S. Garrido's avatar
S. Garrido committed
1796 1797

    // proportion transformations
1798 1799
    float xReduction = sizeX / float(out.cols);
    float yReduction = sizeY / float(out.rows);
S. Garrido's avatar
S. Garrido committed
1800 1801 1802 1803

    // determine the zone where the markers are placed
    if(xReduction > yReduction) {
        int nRows = int(sizeY / xReduction);
1804 1805
        int rowsMargins = (out.rows - nRows) / 2;
        out.adjustROI(-rowsMargins, -rowsMargins, 0, 0);
S. Garrido's avatar
S. Garrido committed
1806 1807
    } else {
        int nCols = int(sizeX / yReduction);
1808 1809
        int colsMargins = (out.cols - nCols) / 2;
        out.adjustROI(0, 0, -colsMargins, -colsMargins);
S. Garrido's avatar
S. Garrido committed
1810 1811 1812
    }

    // now paint each marker
1813
    Dictionary &dictionary = *(_board->dictionary);
1814 1815 1816
    Mat marker;
    Point2f outCorners[3];
    Point2f inCorners[3];
1817
    for(unsigned int m = 0; m < _board->objPoints.size(); m++) {
S. Garrido's avatar
S. Garrido committed
1818
        // transform corners to markerZone coordinates
1819 1820 1821 1822 1823 1824
        for(int j = 0; j < 3; j++) {
            Point2f pf = Point2f(_board->objPoints[m][j].x, _board->objPoints[m][j].y);
            // move top left to 0, 0
            pf -= Point2f(minX, minY);
            pf.x = pf.x / sizeX * float(out.cols);
            pf.y = (1.0f - pf.y / sizeY) * float(out.rows);
1825
            outCorners[j] = pf;
S. Garrido's avatar
S. Garrido committed
1826 1827
        }

1828 1829
        // get marker
        Size dst_sz(outCorners[2] - outCorners[0]); // assuming CCW order
1830
        dst_sz.width = dst_sz.height = std::min(dst_sz.width, dst_sz.height); //marker should be square
1831 1832 1833 1834 1835 1836 1837
        dictionary.drawMarker(_board->ids[m], dst_sz.width, marker, borderBits);

        if((outCorners[0].y == outCorners[1].y) && (outCorners[1].x == outCorners[2].x)) {
            // marker is aligned to image axes
            marker.copyTo(out(Rect(outCorners[0], dst_sz)));
            continue;
        }
S. Garrido's avatar
S. Garrido committed
1838 1839

        // interpolate tiny marker to marker position in markerZone
1840 1841 1842
        inCorners[0] = Point2f(-0.5f, -0.5f);
        inCorners[1] = Point2f(marker.cols - 0.5f, -0.5f);
        inCorners[2] = Point2f(marker.cols - 0.5f, marker.rows - 0.5f);
S. Garrido's avatar
S. Garrido committed
1843 1844

        // remove perspective
1845 1846 1847
        Mat transformation = getAffineTransform(inCorners, outCorners);
        warpAffine(marker, out, transformation, out.size(), INTER_LINEAR,
                        BORDER_TRANSPARENT);
S. Garrido's avatar
S. Garrido committed
1848 1849 1850 1851 1852
    }
}



1853 1854
/**
 */
1855
void drawPlanarBoard(const Ptr<Board> &_board, Size outSize, OutputArray _img, int marginSize,
1856 1857 1858 1859 1860 1861
                     int borderBits) {
    _drawPlanarBoardImpl(_board, outSize, _img, marginSize, borderBits);
}



S. Garrido's avatar
S. Garrido committed
1862
/**
1863
 */
S. Garrido's avatar
S. Garrido committed
1864
double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter,
1865
                            const Ptr<Board> &board, Size imageSize, InputOutputArray _cameraMatrix,
S. Garrido's avatar
S. Garrido committed
1866
                            InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs,
1867 1868 1869 1870 1871
                            OutputArrayOfArrays _tvecs,
                            OutputArray _stdDeviationsIntrinsics,
                            OutputArray _stdDeviationsExtrinsics,
                            OutputArray _perViewErrors,
                            int flags, TermCriteria criteria) {
S. Garrido's avatar
S. Garrido committed
1872 1873 1874 1875

    // for each frame, get properly processed imagePoints and objectPoints for the calibrateCamera
    // function
    vector< Mat > processedObjectPoints, processedImagePoints;
folz's avatar
folz committed
1876
    size_t nFrames = _counter.total();
folz's avatar
folz committed
1877 1878 1879
    int markerCounter = 0;
    for(size_t frame = 0; frame < nFrames; frame++) {
        int nMarkersInThisFrame =  _counter.getMat().ptr< int >()[frame];
S. Garrido's avatar
S. Garrido committed
1880 1881
        vector< Mat > thisFrameCorners;
        vector< int > thisFrameIds;
folz's avatar
folz committed
1882 1883 1884 1885 1886 1887

        CV_Assert(nMarkersInThisFrame > 0);

        thisFrameCorners.reserve((size_t) nMarkersInThisFrame);
        thisFrameIds.reserve((size_t) nMarkersInThisFrame);
        for(int j = markerCounter; j < markerCounter + nMarkersInThisFrame; j++) {
S. Garrido's avatar
S. Garrido committed
1888 1889 1890 1891 1892
            thisFrameCorners.push_back(_corners.getMat(j));
            thisFrameIds.push_back(_ids.getMat().ptr< int >()[j]);
        }
        markerCounter += nMarkersInThisFrame;
        Mat currentImgPoints, currentObjPoints;
1893 1894
        getBoardObjectAndImagePoints(board, thisFrameCorners, thisFrameIds, currentObjPoints,
            currentImgPoints);
S. Garrido's avatar
S. Garrido committed
1895 1896 1897 1898 1899 1900 1901
        if(currentImgPoints.total() > 0 && currentObjPoints.total() > 0) {
            processedImagePoints.push_back(currentImgPoints);
            processedObjectPoints.push_back(currentObjPoints);
        }
    }

    return calibrateCamera(processedObjectPoints, processedImagePoints, imageSize, _cameraMatrix,
1902 1903 1904 1905 1906 1907 1908 1909 1910
                           _distCoeffs, _rvecs, _tvecs, _stdDeviationsIntrinsics, _stdDeviationsExtrinsics,
                           _perViewErrors, flags, criteria);
}



/**
 */
double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter,
1911
  const Ptr<Board> &board, Size imageSize, InputOutputArray _cameraMatrix,
1912 1913 1914 1915
  InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs,
  OutputArrayOfArrays _tvecs, int flags, TermCriteria criteria) {
    return calibrateCameraAruco(_corners, _ids, _counter, board, imageSize, _cameraMatrix, _distCoeffs, _rvecs, _tvecs,
      noArray(), noArray(), noArray(), flags, criteria);
S. Garrido's avatar
S. Garrido committed
1916
}
1917 1918 1919



S. Garrido's avatar
S. Garrido committed
1920 1921
}
}