aruco.hpp
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 #ifndef __OPENCV_ARUCO_HPP__
40 #define __OPENCV_ARUCO_HPP__
41 
42 #include <opencv2/core.hpp>
43 #include <vector>
45 
75 namespace cv {
76 namespace aruco {
77 
80 
86 };
87 
150 struct CV_EXPORTS_W DetectorParameters {
151 
153 
154  CV_WRAP static Ptr<DetectorParameters> create();
155 
156  CV_PROP_RW int adaptiveThreshWinSizeMin;
157  CV_PROP_RW int adaptiveThreshWinSizeMax;
159  CV_PROP_RW double adaptiveThreshConstant;
160  CV_PROP_RW double minMarkerPerimeterRate;
161  CV_PROP_RW double maxMarkerPerimeterRate;
162  CV_PROP_RW double polygonalApproxAccuracyRate;
163  CV_PROP_RW double minCornerDistanceRate;
164  CV_PROP_RW int minDistanceToBorder;
165  CV_PROP_RW double minMarkerDistanceRate;
166  CV_PROP_RW int cornerRefinementMethod;
167  CV_PROP_RW int cornerRefinementWinSize;
169  CV_PROP_RW double cornerRefinementMinAccuracy;
170  CV_PROP_RW int markerBorderBits;
173  CV_PROP_RW double maxErroneousBitsInBorderRate;
174  CV_PROP_RW double minOtsuStdDev;
175  CV_PROP_RW double errorCorrectionRate;
176 
177  // April :: User-configurable parameters.
178  CV_PROP_RW float aprilTagQuadDecimate;
179  CV_PROP_RW float aprilTagQuadSigma;
180 
181  // April :: Internal variables
182  CV_PROP_RW int aprilTagMinClusterPixels;
183  CV_PROP_RW int aprilTagMaxNmaxima;
184  CV_PROP_RW float aprilTagCriticalRad;
185  CV_PROP_RW float aprilTagMaxLineFitMse;
187  CV_PROP_RW int aprilTagDeglitch;
188 
189  // to detect white (inverted) markers
190  CV_PROP_RW bool detectInvertedMarker;
191 };
192 
193 
194 
221 CV_EXPORTS_W void detectMarkers(InputArray image, const Ptr<Dictionary> &dictionary, OutputArrayOfArrays corners,
222  OutputArray ids, const Ptr<DetectorParameters> &parameters = DetectorParameters::create(),
223  OutputArrayOfArrays rejectedImgPoints = noArray(), InputArray cameraMatrix= noArray(), InputArray distCoeff= noArray());
224 
225 
226 
256 CV_EXPORTS_W void estimatePoseSingleMarkers(InputArrayOfArrays corners, float markerLength,
257  InputArray cameraMatrix, InputArray distCoeffs,
258  OutputArray rvecs, OutputArray tvecs, OutputArray _objPoints = noArray());
259 
260 
261 
272 class CV_EXPORTS_W Board {
273 
274  public:
283  CV_WRAP static Ptr<Board> create(InputArrayOfArrays objPoints, const Ptr<Dictionary> &dictionary, InputArray ids);
286  CV_PROP std::vector< std::vector< Point3f > > objPoints;
287 
289  CV_PROP Ptr<Dictionary> dictionary;
290 
293  CV_PROP std::vector< int > ids;
294 };
295 
296 
297 
303 class CV_EXPORTS_W GridBoard : public Board {
304 
305  public:
317  CV_WRAP void draw(Size outSize, OutputArray img, int marginSize = 0, int borderBits = 1);
318 
319 
334  CV_WRAP static Ptr<GridBoard> create(int markersX, int markersY, float markerLength,
335  float markerSeparation, const Ptr<Dictionary> &dictionary, int firstMarker = 0);
336 
340  CV_WRAP Size getGridSize() const { return Size(_markersX, _markersY); }
341 
345  CV_WRAP float getMarkerLength() const { return _markerLength; }
346 
350  CV_WRAP float getMarkerSeparation() const { return _markerSeparation; }
351 
352 
353  private:
354  // number of markers in X and Y directions
355  int _markersX, _markersY;
356 
357  // marker side lenght (normally in meters)
359 
360  // separation between markers in the grid
362 };
363 
364 
365 
394 CV_EXPORTS_W int estimatePoseBoard(InputArrayOfArrays corners, InputArray ids, const Ptr<Board> &board,
395  InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec,
396  OutputArray tvec, bool useExtrinsicGuess = false);
397 
398 
399 
400 
432 CV_EXPORTS_W void refineDetectedMarkers(
433  InputArray image,const Ptr<Board> &board, InputOutputArrayOfArrays detectedCorners,
434  InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners,
435  InputArray cameraMatrix = noArray(), InputArray distCoeffs = noArray(),
436  float minRepDistance = 10.f, float errorCorrectionRate = 3.f, bool checkAllOrders = true,
437  OutputArray recoveredIdxs = noArray(), const Ptr<DetectorParameters> &parameters = DetectorParameters::create());
438 
439 
440 
458 CV_EXPORTS_W void drawDetectedMarkers(InputOutputArray image, InputArrayOfArrays corners,
459  InputArray ids = noArray(),
460  Scalar borderColor = Scalar(0, 255, 0));
461 
462 
463 
482 CV_EXPORTS_W void drawAxis(InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs,
483  InputArray rvec, InputArray tvec, float length);
484 
485 
486 
499 CV_EXPORTS_W void drawMarker(const Ptr<Dictionary> &dictionary, int id, int sidePixels, OutputArray img,
500  int borderBits = 1);
501 
502 
503 
519 CV_EXPORTS_W void drawPlanarBoard(const Ptr<Board> &board, Size outSize, OutputArray img,
520  int marginSize = 0, int borderBits = 1);
521 
522 
523 
527 void _drawPlanarBoardImpl(Board *board, Size outSize, OutputArray img,
528  int marginSize = 0, int borderBits = 1);
529 
530 
531 
568 CV_EXPORTS_AS(calibrateCameraArucoExtended) double calibrateCameraAruco(
569  InputArrayOfArrays corners, InputArray ids, InputArray counter, const Ptr<Board> &board,
570  Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
571  OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
572  OutputArray stdDeviationsIntrinsics, OutputArray stdDeviationsExtrinsics,
573  OutputArray perViewErrors, int flags = 0,
574  TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
575 
576 
579 CV_EXPORTS_W double calibrateCameraAruco(
580  InputArrayOfArrays corners, InputArray ids, InputArray counter, const Ptr<Board> &board,
581  Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
582  OutputArrayOfArrays rvecs = noArray(), OutputArrayOfArrays tvecs = noArray(), int flags = 0,
583  TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
584 
585 
596 CV_EXPORTS_W void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners,
597  InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints);
598 
599 
601 }
602 }
603 
604 #endif
CV_PROP_RW double polygonalApproxAccuracyRate
Definition: aruco.hpp:162
CV_EXPORTS_AS(calibrateCameraCharucoExtended) double calibrateCameraCharuco(InputArrayOfArrays charucoCorners
Calibrate a camera using Charuco corners.
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
Parameters for the detectMarker process:
Definition: aruco.hpp:150
InputArray InputArray counter
Definition: aruco.hpp:569
CV_PROP_RW int perspectiveRemovePixelPerCell
Definition: aruco.hpp:171
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
float _markerSeparation
Definition: aruco.hpp:361
CV_WRAP float getMarkerLength() const
Definition: aruco.hpp:345
CV_PROP_RW int aprilTagMinWhiteBlackDiff
Definition: aruco.hpp:186
CV_PROP_RW float aprilTagMaxLineFitMse
Definition: aruco.hpp:185
CV_PROP_RW double minMarkerDistanceRate
Definition: aruco.hpp:165
CV_PROP_RW int adaptiveThreshWinSizeMin
Definition: aruco.hpp:156
CV_PROP_RW int aprilTagMinClusterPixels
Definition: aruco.hpp:182
Definition: charuco.hpp:47
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray distCoeffs
Definition: charuco.hpp:245
length
Definition: genmap.py:42
CV_PROP_RW double adaptiveThreshConstant
Definition: aruco.hpp:159
CV_PROP_RW int cornerRefinementMaxIterations
Definition: aruco.hpp:168
Tag and corners detection based on the ArUco approach.
Definition: aruco.hpp:82
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int TermCriteria criteria
Definition: charuco.hpp:250
CV_PROP_RW int cornerRefinementMethod
Definition: aruco.hpp:166
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
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray stdDeviationsExtrinsics
Definition: charuco.hpp:245
CV_PROP_RW int cornerRefinementWinSize
Definition: aruco.hpp:167
CV_PROP_RW int aprilTagMaxNmaxima
Definition: aruco.hpp:183
CV_PROP_RW int adaptiveThreshWinSizeMax
Definition: aruco.hpp:157
CV_PROP_RW int minDistanceToBorder
Definition: aruco.hpp:164
Board of markers.
Definition: aruco.hpp:272
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray perViewErrors
Definition: charuco.hpp:245
CV_PROP_RW float aprilTagQuadDecimate
Definition: aruco.hpp:178
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int flags
Definition: charuco.hpp:249
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray stdDeviationsIntrinsics
Definition: charuco.hpp:245
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
CV_PROP_RW double maxMarkerPerimeterRate
Definition: aruco.hpp:161
CV_PROP std::vector< std::vector< Point3f > > objPoints
Definition: aruco.hpp:286
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
CV_PROP_RW bool detectInvertedMarker
Definition: aruco.hpp:190
CV_PROP_RW int adaptiveThreshWinSizeStep
Definition: aruco.hpp:158
CV_PROP_RW int markerBorderBits
Definition: aruco.hpp:170
CV_PROP_RW double cornerRefinementMinAccuracy
Definition: aruco.hpp:169
CV_PROP_RW double maxErroneousBitsInBorderRate
Definition: aruco.hpp:173
CornerRefineMethod
Definition: aruco.hpp:81
CV_PROP_RW double minMarkerPerimeterRate
Definition: aruco.hpp:160
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
CV_WRAP float getMarkerSeparation() const
Definition: aruco.hpp:350
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
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
static CV_WRAP Ptr< DetectorParameters > create()
Create a new set of DetectorParameters with default values.
Definition: aruco.cpp:96
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
InputArray ids
Definition: aruco.hpp:569
CV_PROP_RW float aprilTagCriticalRad
Definition: aruco.hpp:184
Planar board with grid arrangement of markers More common type of board. All markers are placed in th...
Definition: aruco.hpp:303
CV_PROP_RW double errorCorrectionRate
Definition: aruco.hpp:175
CV_PROP std::vector< int > ids
Definition: aruco.hpp:293
CV_PROP_RW int aprilTagDeglitch
Definition: aruco.hpp:187
CV_WRAP Size getGridSize() const
Definition: aruco.hpp:340
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.
CV_PROP_RW float aprilTagQuadSigma
Definition: aruco.hpp:179
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