Classes | Typedefs | Enumerations | Functions | Variables
cv::aruco Namespace Reference

Classes

class  Board
 Board of markers. More...
 
class  CharucoBoard
 ChArUco board Specific class for ChArUco boards. A ChArUco board is a planar board where the markers are placed inside the white squares of a chessboard. The benefits of ChArUco boards is that they provide both, ArUco markers versatility and chessboard corner precision, which is important for calibration and pose estimation. This class also allows the easy creation and drawing of ChArUco boards. More...
 
class  CharucoSubpixelParallel
 
class  DetectInitialCandidatesParallel
 
struct  DetectorParameters
 Parameters for the detectMarker process: More...
 
class  Dictionary
 Dictionary/Set of markers. It contains the inner codification. More...
 
class  GridBoard
 Planar board with grid arrangement of markers More common type of board. All markers are placed in the same plane in a grid arrangement. The board can be drawn using drawPlanarBoard() function (. More...
 
class  IdentifyCandidatesParallel
 
struct  line_fit_pt
 
class  MarkerContourParallel
 
class  MarkerSubpixelParallel
 
struct  pt
 
struct  remove_vertex
 
struct  segment
 
class  SinglePoseEstimationParallel
 
struct  sQuad
 
struct  ufrec
 
struct  uint64_zarray_entry
 
struct  unionfind
 
struct  zarray
 
struct  zmaxheap
 
struct  zmaxheap_iterator
 

Typedefs

typedef struct unionfind unionfind_t
 
typedef struct zarray zarray_t
 
typedef struct zmaxheap_iterator zmaxheap_iterator_t
 
typedef struct zmaxheap zmaxheap_t
 

Enumerations

enum  CornerRefineMethod { CORNER_REFINE_NONE, CORNER_REFINE_SUBPIX, CORNER_REFINE_CONTOUR, CORNER_REFINE_APRILTAG }
 
enum  PREDEFINED_DICTIONARY_NAME {
  DICT_4X4_50 = 0, DICT_4X4_100, DICT_4X4_250, DICT_4X4_1000,
  DICT_5X5_50, DICT_5X5_100, DICT_5X5_250, DICT_5X5_1000,
  DICT_6X6_50, DICT_6X6_100, DICT_6X6_250, DICT_6X6_1000,
  DICT_7X7_50, DICT_7X7_100, DICT_7X7_250, DICT_7X7_1000,
  DICT_ARUCO_ORIGINAL, DICT_APRILTAG_16h5, DICT_APRILTAG_25h9, DICT_APRILTAG_36h10,
  DICT_APRILTAG_36h11
}
 Predefined markers dictionaries/sets Each dictionary indicates the number of bits and the number of markers contained. More...
 

Functions

static void _apriltag (Mat im_orig, const Ptr< DetectorParameters > &_params, std::vector< std::vector< Point2f > > &candidates, std::vector< std::vector< Point > > &contours)
 
static bool _arePointsEnoughForPoseEstimation (const vector< Point3f > &points)
 
static void _convertToGrey (InputArray _in, OutputArray _out)
 Convert input image to gray if it is a 3-channels image. More...
 
static void _copyVector2Output (vector< vector< Point2f > > &vec, OutputArrayOfArrays out)
 Copy the contents of a corners vector to an OutputArray, settings its size. More...
 
static void _detectCandidates (InputArray _image, vector< vector< Point2f > > &candidatesOut, vector< vector< Point > > &contoursOut, const Ptr< DetectorParameters > &_params)
 Detect square candidates in the input image. More...
 
static void _detectInitialCandidates (const Mat &grey, vector< vector< Point2f > > &candidates, vector< vector< Point > > &contours, const Ptr< DetectorParameters > &params)
 Initial steps on finding square candidates. More...
 
static void _distortPoints (vector< cv::Point2f > &in, const Mat &camMatrix, const Mat &distCoeff)
 
void _drawPlanarBoardImpl (Board *board, Size outSize, OutputArray img, int marginSize=0, int borderBits=1)
 Implementation of drawPlanarBoard that accepts a raw Board pointer. More...
 
static Mat _extractBits (InputArray _image, InputArray _corners, int markerSize, int markerBorderBits, int cellSize, double cellMarginRate, double minStdDevOtsu)
 Given an input image and candidate corners, extract the bits of the candidate, including the border bits. More...
 
static int _filterCornersWithoutMinMarkers (const Ptr< CharucoBoard > &_board, InputArray _allCharucoCorners, InputArray _allCharucoIds, InputArray _allArucoIds, int minMarkers, OutputArray _filteredCharucoCorners, OutputArray _filteredCharucoIds)
 
static void _filterDetectedMarkers (vector< vector< Point2f > > &_corners, vector< int > &_ids, vector< vector< Point > > &_contours)
 Final filter of markers after its identification. More...
 
static void _filterTooCloseCandidates (const vector< vector< Point2f > > &candidatesIn, vector< vector< Point2f > > &candidatesOut, const vector< vector< Point > > &contoursIn, vector< vector< Point > > &contoursOut, double minMarkerDistanceRate)
 Check candidates that are too close to each other and remove the smaller one. More...
 
static void _findMarkerContours (InputArray _in, vector< vector< Point2f > > &candidates, vector< vector< Point > > &contoursOut, double minPerimeterRate, double maxPerimeterRate, double accuracyRate, double minCornerDistanceRate, int minDistanceToBorder)
 Given a tresholded image, find the contours, calculate their polygonal approximation and take those that accomplish some conditions. More...
 
static Mat _generateRandomMarker (int markerSize, RNG &rng)
 Generates a random marker Mat of size markerSize x markerSize. More...
 
static int _getBorderErrors (const Mat &bits, int markerSize, int borderSize)
 Return number of erroneous bits in border, i.e. number of white bits in border. More...
 
static Point2f _getCrossPoint (Point3f nLine1, Point3f nLine2)
 
static void _getMaximumSubPixWindowSizes (InputArrayOfArrays markerCorners, InputArray markerIds, InputArray charucoCorners, const Ptr< CharucoBoard > &board, vector< Size > &sizes)
 
static int _getSelfDistance (const Mat &marker)
 Calculate selfDistance of the codification of a marker Mat. Self distance is the Hamming distance of the marker to itself in the other rotations. See S. Garrido-Jurado, R. Muñoz-Salinas, F. J. Madrid-Cuevas, and M. J. Marín-Jiménez. 2014. "Automatic generation and detection of highly reliable fiducial markers under occlusion". Pattern Recogn. 47, 6 (June 2014), 2280-2292. DOI=10.1016/j.patcog.2014.01.005. More...
 
static void _getSingleMarkerObjectPoints (float markerLength, OutputArray _objPoints)
 Return object points for the system centered in a single marker, given the marker length. More...
 
static void _identifyCandidates (InputArray _image, vector< vector< Point2f > > &_candidates, vector< vector< Point > > &_contours, const Ptr< Dictionary > &_dictionary, vector< vector< Point2f > > &_accepted, vector< int > &ids, const Ptr< DetectorParameters > &params, OutputArrayOfArrays _rejected=noArray())
 Identify square candidates according to a marker dictionary. More...
 
static bool _identifyOneCandidate (const Ptr< Dictionary > &dictionary, InputArray _image, vector< Point2f > &_corners, int &idx, const Ptr< DetectorParameters > &params)
 Tries to identify one candidate given the dictionary. More...
 
static Point3f _interpolate2Dline (const std::vector< cv::Point2f > &nContours)
 
static int _interpolateCornersCharucoApproxCalib (InputArrayOfArrays _markerCorners, InputArray _markerIds, InputArray _image, const Ptr< CharucoBoard > &_board, InputArray _cameraMatrix, InputArray _distCoeffs, OutputArray _charucoCorners, OutputArray _charucoIds)
 
static int _interpolateCornersCharucoLocalHom (InputArrayOfArrays _markerCorners, InputArray _markerIds, InputArray _image, const Ptr< CharucoBoard > &_board, OutputArray _charucoCorners, OutputArray _charucoIds)
 
static void _projectUndetectedMarkers (const Ptr< Board > &_board, InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds, InputArray _cameraMatrix, InputArray _distCoeffs, vector< vector< Point2f > > &_undetectedMarkersProjectedCorners, OutputArray _undetectedMarkersIds)
 
static void _projectUndetectedMarkers (const Ptr< Board > &_board, InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds, vector< vector< Point2f > > &_undetectedMarkersProjectedCorners, OutputArray _undetectedMarkersIds)
 
static void _refineCandidateLines (std::vector< Point > &nContours, std::vector< Point2f > &nCorners, const Mat &camMatrix, const Mat &distCoeff)
 
static void _reorderCandidatesCorners (vector< vector< Point2f > > &candidates)
 Assure order of candidate corners is clockwise direction. More...
 
static int _selectAndRefineChessboardCorners (InputArray _allCorners, InputArray _image, OutputArray _selectedCorners, OutputArray _selectedIds, const vector< Size > &winSizes)
 From all projected chessboard corners, select those inside the image and apply subpixel refinement. Returns number of valid corners. More...
 
static void _swap_default (zmaxheap_t *heap, int a, int b)
 
static void _swap_pointer (zmaxheap_t *heap, int a, int b)
 
static void _threshold (InputArray _in, OutputArray _out, int winSize, double constant)
 Threshold input image using adaptive thresholding. More...
 
static void _zarray_add (zarray_t *za, const void *p)
 
static zarray_t_zarray_create (size_t el_sz)
 
static void _zarray_destroy (zarray_t *za)
 
static void _zarray_ensure_capacity (zarray_t *za, int capacity)
 
static void _zarray_get (const zarray_t *za, int idx, void *p)
 
static void _zarray_get_volatile (const zarray_t *za, int idx, void *p)
 
static void _zarray_set (zarray_t *za, int idx, const void *p, void *outp)
 
static int _zarray_size (const zarray_t *za)
 
static void _zarray_truncate (zarray_t *za, int sz)
 
static void _zmaxheap_ensure_capacity (zmaxheap_t *heap, int capacity)
 
zarray_tapriltag_quad_thresh (const Ptr< DetectorParameters > &parameters, const Mat &mImg, std::vector< std::vector< Point > > &contours)
 
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's the same function as calibrateCameraAruco but without calibration error estimation. More...
 
double calibrateCameraAruco (InputArrayOfArrays _corners, InputArray _ids, InputArray _counter, const Ptr< Board > &board, Size imageSize, InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs, OutputArray _stdDeviationsIntrinsics, OutputArray _stdDeviationsExtrinsics, OutputArray _perViewErrors, int flags, TermCriteria criteria)
 
CV_EXPORTS_W double calibrateCameraCharuco (InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds, const Ptr< CharucoBoard > &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's the same function as calibrateCameraCharuco but without calibration error estimation. More...
 
double calibrateCameraCharuco (InputArrayOfArrays _charucoCorners, InputArrayOfArrays _charucoIds, const Ptr< CharucoBoard > &_board, Size imageSize, InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs, OutputArray _stdDeviationsIntrinsics, OutputArray _stdDeviationsExtrinsics, OutputArray _perViewErrors, int flags, TermCriteria criteria)
 
 CV_EXPORTS_AS (custom_dictionary) Ptr< Dictionary > generateCustomDictionary(int nMarkers
 
 CV_EXPORTS_AS (custom_dictionary_from) Ptr< Dictionary > generateCustomDictionary(int nMarkers
 Generates a new customizable marker dictionary. More...
 
 CV_EXPORTS_AS (calibrateCameraCharucoExtended) double calibrateCameraCharuco(InputArrayOfArrays charucoCorners
 Calibrate a camera using Charuco corners. More...
 
 CV_EXPORTS_AS (calibrateCameraArucoExtended) double calibrateCameraAruco(InputArrayOfArrays corners
 Calibrate a camera using aruco markers. More...
 
CV_EXPORTS_W void detectCharucoDiamond (InputArray image, InputArrayOfArrays markerCorners, InputArray markerIds, float squareMarkerLengthRate, OutputArrayOfArrays diamondCorners, OutputArray diamondIds, InputArray cameraMatrix=noArray(), InputArray distCoeffs=noArray())
 Detect ChArUco Diamond markers. More...
 
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. More...
 
void detectMarkers (InputArray _image, const Ptr< Dictionary > &_dictionary, OutputArrayOfArrays _corners, OutputArray _ids, const Ptr< DetectorParameters > &_params, OutputArrayOfArrays _rejectedImgPoints, InputArrayOfArrays camMatrix, InputArrayOfArrays distCoeff)
 
static void do_quad (int nCidx0, int nCidx1, zarray_t &nClusters, int nW, int nH, zarray_t *nquads, const Ptr< DetectorParameters > &td, const Mat im)
 
static void do_unionfind_line (unionfind_t *uf, Mat &im, int w, int s, int y)
 
CV_EXPORTS_W void drawAxis (InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs, InputArray rvec, InputArray tvec, float length)
 Draw coordinate system axis from pose estimation. More...
 
CV_EXPORTS void drawCharucoDiamond (const Ptr< Dictionary > &dictionary, Vec4i ids, int squareLength, int markerLength, OutputArray img, int marginSize=0, int borderBits=1)
 Draw a ChArUco Diamond marker. More...
 
CV_EXPORTS_W void drawDetectedCornersCharuco (InputOutputArray image, InputArray charucoCorners, InputArray charucoIds=noArray(), Scalar cornerColor=Scalar(255, 0, 0))
 Draws a set of Charuco corners. More...
 
CV_EXPORTS_W void drawDetectedDiamonds (InputOutputArray image, InputArrayOfArrays diamondCorners, InputArray diamondIds=noArray(), Scalar borderColor=Scalar(0, 0, 255))
 Draw a set of detected ChArUco Diamond markers. More...
 
CV_EXPORTS_W void drawDetectedMarkers (InputOutputArray image, InputArrayOfArrays corners, InputArray ids=noArray(), Scalar borderColor=Scalar(0, 255, 0))
 Draw detected markers in image. More...
 
CV_EXPORTS_W void drawMarker (const Ptr< Dictionary > &dictionary, int id, int sidePixels, OutputArray img, int borderBits=1)
 Draw a canonical marker image. More...
 
CV_EXPORTS_W void drawPlanarBoard (const Ptr< Board > &board, Size outSize, OutputArray img, int marginSize=0, int borderBits=1)
 Draw a planar board. More...
 
int err_compare_descending (const void *_a, const void *_b)
 
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. More...
 
CV_EXPORTS_W bool estimatePoseCharucoBoard (InputArray charucoCorners, InputArray charucoIds, const Ptr< CharucoBoard > &board, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false)
 Pose estimation for a ChArUco board given some of their corners. More...
 
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. More...
 
void fit_line (struct line_fit_pt *lfps, int sz, int i0, int i1, double *lineparm, double *err, double *mse)
 
int fit_quad (const Ptr< DetectorParameters > &_params, const Mat im, zarray_t *cluster, struct sQuad *quad)
 
Ptr< DictionarygenerateCustomDictionary (int nMarkers, int markerSize, const Ptr< Dictionary > &baseDictionary, int randomSeed)
 
Ptr< DictionarygenerateCustomDictionary (int nMarkers, int markerSize, int randomSeed)
 
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 object points to call solvePnP. More...
 
CV_EXPORTS Ptr< DictionarygetPredefinedDictionary (PREDEFINED_DICTIONARY_NAME name)
 Returns one of the predefined dictionaries defined in PREDEFINED_DICTIONARY_NAME. More...
 
CV_EXPORTS_W Ptr< DictionarygetPredefinedDictionary (int dict)
 Returns one of the predefined dictionaries referenced by DICT_*. More...
 
CV_EXPORTS_W int interpolateCornersCharuco (InputArrayOfArrays markerCorners, InputArray markerIds, InputArray image, const Ptr< CharucoBoard > &board, OutputArray charucoCorners, OutputArray charucoIds, InputArray cameraMatrix=noArray(), InputArray distCoeffs=noArray(), int minMarkers=2)
 Interpolate position of ChArUco board corners. More...
 
static void ptsort (struct pt *pts, int sz)
 
static void ptsort_ (struct pt *pts, int sz)
 
int quad_segment_agg (int sz, struct line_fit_pt *lfps, int indices[4])
 
int quad_segment_maxima (const Ptr< DetectorParameters > &td, int sz, struct line_fit_pt *lfps, int indices[4])
 
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. More...
 
void threshold (const Mat mIm, const Ptr< DetectorParameters > &parameters, Mat &mThresh)
 
static uint32_t u64hash_2 (uint64_t x)
 
static uint32_t unionfind_connect (unionfind_t *uf, uint32_t aid, uint32_t bid)
 
static unionfind_tunionfind_create (uint32_t maxid)
 
static void unionfind_destroy (unionfind_t *uf)
 
static uint32_t unionfind_get_representative (unionfind_t *uf, uint32_t id)
 
static uint32_t unionfind_get_set_size (unionfind_t *uf, uint32_t id)
 
void zmaxheap_add (zmaxheap_t *heap, void *p, float v)
 
zmaxheap_tzmaxheap_create (size_t el_sz)
 
void zmaxheap_destroy (zmaxheap_t *heap)
 
static int zmaxheap_remove_index (zmaxheap_t *heap, int idx, void *p, float *v)
 
int zmaxheap_remove_max (zmaxheap_t *heap, void *p, float *v)
 

Variables

int const Ptr< Dictionary > & baseDictionary
 
InputArrayOfArrays const Ptr< CharucoBoard > & board
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray cameraMatrix
 
InputArrayOfArrays charucoIds
 
InputArray InputArray counter
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON))
 
const Dictionary DICT_4X4_1000_DATA = Dictionary(Mat(1000, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 0)
 
const Dictionary DICT_4X4_100_DATA = Dictionary(Mat(100, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 1)
 
const Dictionary DICT_4X4_250_DATA = Dictionary(Mat(250, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 1)
 
const Dictionary DICT_4X4_50_DATA = Dictionary(Mat(50, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 1)
 
const Dictionary DICT_5X5_1000_DATA = Dictionary(Mat(1000, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 2)
 
const Dictionary DICT_5X5_100_DATA = Dictionary(Mat(100, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 3)
 
const Dictionary DICT_5X5_250_DATA = Dictionary(Mat(250, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 2)
 
const Dictionary DICT_5X5_50_DATA = Dictionary(Mat(50, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 3)
 
const Dictionary DICT_6X6_1000_DATA = Dictionary(Mat(1000, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 4)
 
const Dictionary DICT_6X6_100_DATA = Dictionary(Mat(100, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 5)
 
const Dictionary DICT_6X6_250_DATA = Dictionary(Mat(250, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 5)
 
const Dictionary DICT_6X6_50_DATA = Dictionary(Mat(50, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 6)
 
const Dictionary DICT_7X7_1000_DATA = Dictionary(Mat(1000, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 6)
 
const Dictionary DICT_7X7_100_DATA = Dictionary(Mat(100, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 8)
 
const Dictionary DICT_7X7_250_DATA = Dictionary(Mat(250, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 8)
 
const Dictionary DICT_7X7_50_DATA = Dictionary(Mat(50, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 9)
 
const Dictionary DICT_APRILTAG_16h5_DATA = Dictionary(Mat(30, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_16h5_BYTES), 4, 0)
 
const Dictionary DICT_APRILTAG_25h9_DATA = Dictionary(Mat(35, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_25h9_BYTES), 5, 0)
 
const Dictionary DICT_APRILTAG_36h10_DATA = Dictionary(Mat(2320, (6*6 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_36h10_BYTES), 6, 0)
 
const Dictionary DICT_APRILTAG_36h11_DATA = Dictionary(Mat(587, (6*6 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_36h11_BYTES), 6, 0)
 
const Dictionary DICT_ARUCO_DATA = Dictionary(Mat(1024, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_ARUCO_BYTES), 5, 0)
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray distCoeffs
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int flags = 0
 
InputArray ids
 
InputArrayOfArrays const Ptr< CharucoBoard > Size imageSize
 
int markerSize
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray perViewErrors
 
int int randomSeed =0)
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays rvecs
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray stdDeviationsExtrinsics
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray stdDeviationsIntrinsics
 
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays tvecs
 

Typedef Documentation

◆ unionfind_t

Definition at line 22 of file unionfind.hpp.

◆ zarray_t

typedef struct zarray cv::aruco::zarray_t

Defines a structure which acts as a resize-able array ala Java's ArrayList.

Definition at line 31 of file zarray.hpp.

◆ zmaxheap_iterator_t

Definition at line 25 of file zmaxheap.hpp.

◆ zmaxheap_t

Definition at line 23 of file zmaxheap.hpp.

Function Documentation

◆ _apriltag()

static void cv::aruco::_apriltag ( Mat  im_orig,
const Ptr< DetectorParameters > &  _params,
std::vector< std::vector< Point2f > > &  candidates,
std::vector< std::vector< Point > > &  contours 
)
static
Parameters
im_orig
_params
candidates
contours

Step 1. Detect quads according to requested image decimation and blurring parameters.

Step 2. do the Threshold :: get the set of candidate quads

Step 3. Save the output :: candidate corners

Definition at line 998 of file aruco.cpp.

◆ _arePointsEnoughForPoseEstimation()

static bool cv::aruco::_arePointsEnoughForPoseEstimation ( const vector< Point3f > &  points)
static

Check if a set of 3d points are enough for calibration. Z coordinate is ignored. Only axis paralel lines are considered

Definition at line 622 of file charuco.cpp.

◆ _convertToGrey()

static void cv::aruco::_convertToGrey ( InputArray  _in,
OutputArray  _out 
)
static

Convert input image to gray if it is a 3-channels image.

Definition at line 105 of file aruco.cpp.

◆ _copyVector2Output()

static void cv::aruco::_copyVector2Output ( vector< vector< Point2f > > &  vec,
OutputArrayOfArrays  out 
)
static

Copy the contents of a corners vector to an OutputArray, settings its size.

Definition at line 591 of file aruco.cpp.

◆ _detectCandidates()

static void cv::aruco::_detectCandidates ( InputArray  _image,
vector< vector< Point2f > > &  candidatesOut,
vector< vector< Point > > &  contoursOut,
const Ptr< DetectorParameters > &  _params 
)
static

Detect square candidates in the input image.

  1. CONVERT TO GRAY
  2. DETECT FIRST SET OF CANDIDATES
  3. SORT CORNERS
  4. FILTER OUT NEAR CANDIDATE PAIRS

Definition at line 373 of file aruco.cpp.

◆ _detectInitialCandidates()

static void cv::aruco::_detectInitialCandidates ( const Mat &  grey,
vector< vector< Point2f > > &  candidates,
vector< vector< Point > > &  contours,
const Ptr< DetectorParameters > &  params 
)
static

Initial steps on finding square candidates.

Definition at line 328 of file aruco.cpp.

◆ _distortPoints()

static void cv::aruco::_distortPoints ( vector< cv::Point2f > &  in,
const Mat &  camMatrix,
const Mat &  distCoeff 
)
static

Definition at line 864 of file aruco.cpp.

◆ _extractBits()

static Mat cv::aruco::_extractBits ( InputArray  _image,
InputArray  _corners,
int  markerSize,
int  markerBorderBits,
int  cellSize,
double  cellMarginRate,
double  minStdDevOtsu 
)
static

Given an input image and candidate corners, extract the bits of the candidate, including the border bits.

Definition at line 401 of file aruco.cpp.

◆ _filterCornersWithoutMinMarkers()

static int cv::aruco::_filterCornersWithoutMinMarkers ( const Ptr< CharucoBoard > &  _board,
InputArray  _allCharucoCorners,
InputArray  _allCharucoIds,
InputArray  _allArucoIds,
int  minMarkers,
OutputArray  _filteredCharucoCorners,
OutputArray  _filteredCharucoIds 
)
static

Remove charuco corners if any of their minMarkers closest markers has not been detected

Definition at line 234 of file charuco.cpp.

◆ _filterDetectedMarkers()

static void cv::aruco::_filterDetectedMarkers ( vector< vector< Point2f > > &  _corners,
vector< int > &  _ids,
vector< vector< Point > > &  _contours 
)
static

Final filter of markers after its identification.

Definition at line 688 of file aruco.cpp.

◆ _filterTooCloseCandidates()

static void cv::aruco::_filterTooCloseCandidates ( const vector< vector< Point2f > > &  candidatesIn,
vector< vector< Point2f > > &  candidatesOut,
const vector< vector< Point > > &  contoursIn,
vector< vector< Point > > &  contoursOut,
double  minMarkerDistanceRate 
)
static

Check candidates that are too close to each other and remove the smaller one.

Definition at line 217 of file aruco.cpp.

◆ _findMarkerContours()

static void cv::aruco::_findMarkerContours ( InputArray  _in,
vector< vector< Point2f > > &  candidates,
vector< vector< Point > > &  contoursOut,
double  minPerimeterRate,
double  maxPerimeterRate,
double  accuracyRate,
double  minCornerDistanceRate,
int  minDistanceToBorder 
)
static

Given a tresholded image, find the contours, calculate their polygonal approximation and take those that accomplish some conditions.

Definition at line 131 of file aruco.cpp.

◆ _generateRandomMarker()

static Mat cv::aruco::_generateRandomMarker ( int  markerSize,
RNG &  rng 
)
static

Generates a random marker Mat of size markerSize x markerSize.

Definition at line 365 of file dictionary.cpp.

◆ _getBorderErrors()

static int cv::aruco::_getBorderErrors ( const Mat &  bits,
int  markerSize,
int  borderSize 
)
static

Return number of erroneous bits in border, i.e. number of white bits in border.

Definition at line 471 of file aruco.cpp.

◆ _getCrossPoint()

static Point2f cv::aruco::_getCrossPoint ( Point3f  nLine1,
Point3f  nLine2 
)
static

Find the Point where the lines crosses :: Called from function refineCandidateLines

Parameters
nLine1
nLine2
Returns
Crossed Point

Definition at line 858 of file aruco.cpp.

◆ _getMaximumSubPixWindowSizes()

static void cv::aruco::_getMaximumSubPixWindowSizes ( InputArrayOfArrays  markerCorners,
InputArray  markerIds,
InputArray  charucoCorners,
const Ptr< CharucoBoard > &  board,
vector< Size > &  sizes 
)
static

Calculate the maximum window sizes for corner refinement for each charuco corner based on the distance to their closest markers

Definition at line 386 of file charuco.cpp.

◆ _getSelfDistance()

static int cv::aruco::_getSelfDistance ( const Mat &  marker)
static

Calculate selfDistance of the codification of a marker Mat. Self distance is the Hamming distance of the marker to itself in the other rotations. See S. Garrido-Jurado, R. Muñoz-Salinas, F. J. Madrid-Cuevas, and M. J. Marín-Jiménez. 2014. "Automatic generation and detection of highly reliable fiducial markers under occlusion". Pattern Recogn. 47, 6 (June 2014), 2280-2292. DOI=10.1016/j.patcog.2014.01.005.

Definition at line 383 of file dictionary.cpp.

◆ _getSingleMarkerObjectPoints()

static void cv::aruco::_getSingleMarkerObjectPoints ( float  markerLength,
OutputArray  _objPoints 
)
static

Return object points for the system centered in a single marker, given the marker length.

Definition at line 762 of file aruco.cpp.

◆ _identifyCandidates()

static void cv::aruco::_identifyCandidates ( InputArray  _image,
vector< vector< Point2f > > &  _candidates,
vector< vector< Point > > &  _contours,
const Ptr< Dictionary > &  _dictionary,
vector< vector< Point2f > > &  _accepted,
vector< int > &  ids,
const Ptr< DetectorParameters > &  params,
OutputArrayOfArrays  _rejected = noArray() 
)
static

Identify square candidates according to a marker dictionary.

Definition at line 626 of file aruco.cpp.

◆ _identifyOneCandidate()

static bool cv::aruco::_identifyOneCandidate ( const Ptr< Dictionary > &  dictionary,
InputArray  _image,
vector< Point2f > &  _corners,
int &  idx,
const Ptr< DetectorParameters > &  params 
)
static

Tries to identify one candidate given the dictionary.

Definition at line 497 of file aruco.cpp.

◆ _interpolate2Dline()

static Point3f cv::aruco::_interpolate2Dline ( const std::vector< cv::Point2f > &  nContours)
static

Line fitting A * B = C :: Called from function refineCandidateLines

Parameters
nContours,contour-container

Definition at line 813 of file aruco.cpp.

◆ _interpolateCornersCharucoApproxCalib()

static int cv::aruco::_interpolateCornersCharucoApproxCalib ( InputArrayOfArrays  _markerCorners,
InputArray  _markerIds,
InputArray  _image,
const Ptr< CharucoBoard > &  _board,
InputArray  _cameraMatrix,
InputArray  _distCoeffs,
OutputArray  _charucoCorners,
OutputArray  _charucoIds 
)
static

Interpolate charuco corners using approximated pose estimation

Definition at line 439 of file charuco.cpp.

◆ _interpolateCornersCharucoLocalHom()

static int cv::aruco::_interpolateCornersCharucoLocalHom ( InputArrayOfArrays  _markerCorners,
InputArray  _markerIds,
InputArray  _image,
const Ptr< CharucoBoard > &  _board,
OutputArray  _charucoCorners,
OutputArray  _charucoIds 
)
static

Interpolate charuco corners using local homography

Definition at line 483 of file charuco.cpp.

◆ _projectUndetectedMarkers() [1/2]

static void cv::aruco::_projectUndetectedMarkers ( const Ptr< Board > &  _board,
InputOutputArrayOfArrays  _detectedCorners,
InputOutputArray  _detectedIds,
InputArray  _cameraMatrix,
InputArray  _distCoeffs,
vector< vector< Point2f > > &  _undetectedMarkersProjectedCorners,
OutputArray  _undetectedMarkersIds 
)
static

Project board markers that are not included in the list of detected markers

Definition at line 1290 of file aruco.cpp.

◆ _projectUndetectedMarkers() [2/2]

static void cv::aruco::_projectUndetectedMarkers ( const Ptr< Board > &  _board,
InputOutputArrayOfArrays  _detectedCorners,
InputOutputArray  _detectedIds,
vector< vector< Point2f > > &  _undetectedMarkersProjectedCorners,
OutputArray  _undetectedMarkersIds 
)
static

Interpolate board markers that are not included in the list of detected markers using global homography

Definition at line 1338 of file aruco.cpp.

◆ _refineCandidateLines()

static void cv::aruco::_refineCandidateLines ( std::vector< Point > &  nContours,
std::vector< Point2f > &  nCorners,
const Mat &  camMatrix,
const Mat &  distCoeff 
)
static

Refine Corners using the contour vector :: Called from function detectMarkers

Parameters
nContours,contour-container
nCorners,candidateCorners
camMatrix,cameraMatrixinput 3x3 floating-point camera matrix
distCoeff,distCoeffsvector of distortion coefficient

Definition at line 886 of file aruco.cpp.

◆ _reorderCandidatesCorners()

static void cv::aruco::_reorderCandidatesCorners ( vector< vector< Point2f > > &  candidates)
static

Assure order of candidate corners is clockwise direction.

Definition at line 198 of file aruco.cpp.

◆ _selectAndRefineChessboardCorners()

static int cv::aruco::_selectAndRefineChessboardCorners ( InputArray  _allCorners,
InputArray  _image,
OutputArray  _selectedCorners,
OutputArray  _selectedIds,
const vector< Size > &  winSizes 
)
static

From all projected chessboard corners, select those inside the image and apply subpixel refinement. Returns number of valid corners.

Definition at line 322 of file charuco.cpp.

◆ _swap_default()

static void cv::aruco::_swap_default ( zmaxheap_t heap,
int  a,
int  b 
)
inlinestatic

Definition at line 45 of file zmaxheap.cpp.

◆ _swap_pointer()

static void cv::aruco::_swap_pointer ( zmaxheap_t heap,
int  a,
int  b 
)
inlinestatic

Definition at line 58 of file zmaxheap.cpp.

◆ _threshold()

static void cv::aruco::_threshold ( InputArray  _in,
OutputArray  _out,
int  winSize,
double  constant 
)
static

Threshold input image using adaptive thresholding.

Definition at line 119 of file aruco.cpp.

◆ _zarray_add()

static void cv::aruco::_zarray_add ( zarray_t za,
const void *  p 
)
inlinestatic

Adds a new element to the end of the supplied array, and sets its value (by copying) from the data pointed to by the supplied pointer 'p'. Automatically ensures that enough storage space is available for the new element.

Definition at line 96 of file zarray.hpp.

◆ _zarray_create()

static zarray_t* cv::aruco::_zarray_create ( size_t  el_sz)
inlinestatic

Creates and returns a variable array structure capable of holding elements of the specified size. It is the caller's responsibility to call zarray_destroy() on the returned array when it is no longer needed.

Definition at line 45 of file zarray.hpp.

◆ _zarray_destroy()

static void cv::aruco::_zarray_destroy ( zarray_t za)
inlinestatic

Frees all resources associated with the variable array structure which was created by zarray_create(). After calling, 'za' will no longer be valid for storage.

Definition at line 55 of file zarray.hpp.

◆ _zarray_ensure_capacity()

static void cv::aruco::_zarray_ensure_capacity ( zarray_t za,
int  capacity 
)
inlinestatic

Allocates enough internal storage in the supplied variable array structure to guarantee that the supplied number of elements (capacity) can be safely stored.

Definition at line 78 of file zarray.hpp.

◆ _zarray_get()

static void cv::aruco::_zarray_get ( const zarray_t za,
int  idx,
void *  p 
)
inlinestatic

Retrieves the element from the supplied array located at the zero-based index of 'idx' and copies its value into the variable pointed to by the pointer 'p'.

Definition at line 108 of file zarray.hpp.

◆ _zarray_get_volatile()

static void cv::aruco::_zarray_get_volatile ( const zarray_t za,
int  idx,
void *  p 
)
inlinestatic

Similar to zarray_get(), but returns a "live" pointer to the internal storage, avoiding a memcpy. This pointer is not valid across operations which might move memory around (i.e. zarray_remove_value(), zarray_remove_index(), zarray_insert(), zarray_sort(), zarray_clear()). 'p' should be a pointer to the pointer which will be set to the internal address.

Definition at line 122 of file zarray.hpp.

◆ _zarray_set()

static void cv::aruco::_zarray_set ( zarray_t za,
int  idx,
const void *  p,
void *  outp 
)
inlinestatic

Sets the value of the current element at index 'idx' by copying its value from the data pointed to by 'p'. The previous value of the changed element will be copied into the data pointed to by 'outp' if it is not null.

Definition at line 138 of file zarray.hpp.

◆ _zarray_size()

static int cv::aruco::_zarray_size ( const zarray_t za)
inlinestatic

Retrieves the number of elements currently being contained by the passed array, which may be different from its capacity. The index of the last element in the array will be one less than the returned value.

Definition at line 70 of file zarray.hpp.

◆ _zarray_truncate()

static void cv::aruco::_zarray_truncate ( zarray_t za,
int  sz 
)
inlinestatic

Definition at line 129 of file zarray.hpp.

◆ _zmaxheap_ensure_capacity()

static void cv::aruco::_zmaxheap_ensure_capacity ( zmaxheap_t heap,
int  capacity 
)
static

Definition at line 92 of file zmaxheap.cpp.

◆ apriltag_quad_thresh()

zarray_t * cv::aruco::apriltag_quad_thresh ( const Ptr< DetectorParameters > &  parameters,
const Mat &  mImg,
std::vector< std::vector< Point > > &  contours 
)
Parameters
parameters
mImg
contours
Returns

Definition at line 1316 of file apriltag_quad_thresh.cpp.

◆ calibrateCameraAruco()

double cv::aruco::calibrateCameraAruco ( InputArrayOfArrays  _corners,
InputArray  _ids,
InputArray  _counter,
const Ptr< Board > &  board,
Size  imageSize,
InputOutputArray  _cameraMatrix,
InputOutputArray  _distCoeffs,
OutputArrayOfArrays  _rvecs,
OutputArrayOfArrays  _tvecs,
OutputArray  _stdDeviationsIntrinsics,
OutputArray  _stdDeviationsExtrinsics,
OutputArray  _perViewErrors,
int  flags,
TermCriteria  criteria 
)

Definition at line 1861 of file aruco.cpp.

◆ calibrateCameraCharuco()

double cv::aruco::calibrateCameraCharuco ( InputArrayOfArrays  _charucoCorners,
InputArrayOfArrays  _charucoIds,
const Ptr< CharucoBoard > &  _board,
Size  imageSize,
InputOutputArray  _cameraMatrix,
InputOutputArray  _distCoeffs,
OutputArrayOfArrays  _rvecs,
OutputArrayOfArrays  _tvecs,
OutputArray  _stdDeviationsIntrinsics,
OutputArray  _stdDeviationsExtrinsics,
OutputArray  _perViewErrors,
int  flags,
TermCriteria  criteria 
)

Definition at line 688 of file charuco.cpp.

◆ detectMarkers()

void cv::aruco::detectMarkers ( InputArray  _image,
const Ptr< Dictionary > &  _dictionary,
OutputArrayOfArrays  _corners,
OutputArray  _ids,
const Ptr< DetectorParameters > &  _params,
OutputArrayOfArrays  _rejectedImgPoints,
InputArrayOfArrays  camMatrix,
InputArrayOfArrays  distCoeff 
)

STEP 1: Detect marker candidates

STEP 1.a Detect marker candidates :: using AprilTag

STEP 1.b Detect marker candidates :: traditional way

STEP 2: Check candidate codification (identify markers)

STEP 3: Filter detected markers;

STEP 4: Corner refinement :: use corner subpix

STEP 4, Optional : Corner refinement :: use contour container

Definition at line 1118 of file aruco.cpp.

◆ do_quad()

static void cv::aruco::do_quad ( int  nCidx0,
int  nCidx1,
zarray_t nClusters,
int  nW,
int  nH,
zarray_t nquads,
const Ptr< DetectorParameters > &  td,
const Mat  im 
)
static
Parameters
nCidx0
nCidx1
nClusters
nW
nH
nquads
td
im

Definition at line 1042 of file apriltag_quad_thresh.cpp.

◆ do_unionfind_line()

static void cv::aruco::do_unionfind_line ( unionfind_t uf,
Mat &  im,
int  w,
int  s,
int  y 
)
static

Definition at line 575 of file apriltag_quad_thresh.cpp.

◆ err_compare_descending()

int cv::aruco::err_compare_descending ( const void *  _a,
const void *  _b 
)

Definition at line 263 of file apriltag_quad_thresh.cpp.

◆ fit_line()

void cv::aruco::fit_line ( struct line_fit_pt lfps,
int  sz,
int  i0,
int  i1,
double *  lineparm,
double *  err,
double *  mse 
)

lfps contains cumulative moments for N points, with index j reflecting points [0,j] (inclusive). fit a line to the points [i0, i1] (inclusive). i0, i1 are both (0, sz) if i1 < i0, we treat this as a wrap around.

Definition at line 138 of file apriltag_quad_thresh.cpp.

◆ fit_quad()

int cv::aruco::fit_quad ( const Ptr< DetectorParameters > &  _params,
const Mat  im,
zarray_t cluster,
struct sQuad quad 
)

return 1 if the quad looks okay, 0 if it should be discarded quad

Definition at line 603 of file apriltag_quad_thresh.cpp.

◆ generateCustomDictionary() [1/2]

Ptr<Dictionary> cv::aruco::generateCustomDictionary ( int  nMarkers,
int  markerSize,
const Ptr< Dictionary > &  baseDictionary,
int  randomSeed 
)

Definition at line 395 of file dictionary.cpp.

◆ generateCustomDictionary() [2/2]

Ptr<Dictionary> cv::aruco::generateCustomDictionary ( int  nMarkers,
int  markerSize,
int  randomSeed 
)

Definition at line 487 of file dictionary.cpp.

◆ ptsort()

static void cv::aruco::ptsort ( struct pt pts,
int  sz 
)
inlinestatic

Definition at line 34 of file apriltag_quad_thresh.cpp.

◆ ptsort_()

void cv::aruco::ptsort_ ( struct pt pts,
int  sz 
)
static

Definition at line 91 of file apriltag_quad_thresh.cpp.

◆ quad_segment_agg()

int cv::aruco::quad_segment_agg ( int  sz,
struct line_fit_pt lfps,
int  indices[4] 
)

returns 0 if the cluster looks bad.

Definition at line 459 of file apriltag_quad_thresh.cpp.

◆ quad_segment_maxima()

int cv::aruco::quad_segment_maxima ( const Ptr< DetectorParameters > &  td,
int  sz,
struct line_fit_pt lfps,
int  indices[4] 
)
  1. Identify A) white points near a black point and B) black points near a white point.
  2. Find the connected components within each of the classes above, yielding clusters of "white-near-black" and "black-near-white". (These two classes are kept separate). Each segment has a unique id.
  3. For every pair of "white-near-black" and "black-near-white" clusters, find the set of points that are in one and adjacent to the other. In other words, a "boundary" layer between the two clusters. (This is actually performed by iterating over the pixels, rather than pairs of clusters.) Critically, this helps keep nearby edges from becoming connected.

Definition at line 285 of file apriltag_quad_thresh.cpp.

◆ threshold()

void cv::aruco::threshold ( const Mat  mIm,
const Ptr< DetectorParameters > &  parameters,
Mat &  mThresh 
)
Parameters
mIm
parameters
mThresh

Definition at line 1087 of file apriltag_quad_thresh.cpp.

◆ u64hash_2()

static uint32_t cv::aruco::u64hash_2 ( uint64_t  x)
inlinestatic

Definition at line 30 of file apriltag_quad_thresh.hpp.

◆ unionfind_connect()

static uint32_t cv::aruco::unionfind_connect ( unionfind_t uf,
uint32_t  aid,
uint32_t  bid 
)
inlinestatic

Definition at line 100 of file unionfind.hpp.

◆ unionfind_create()

static unionfind_t* cv::aruco::unionfind_create ( uint32_t  maxid)
inlinestatic

Definition at line 38 of file unionfind.hpp.

◆ unionfind_destroy()

static void cv::aruco::unionfind_destroy ( unionfind_t uf)
inlinestatic

Definition at line 49 of file unionfind.hpp.

◆ unionfind_get_representative()

static uint32_t cv::aruco::unionfind_get_representative ( unionfind_t uf,
uint32_t  id 
)
inlinestatic

Definition at line 73 of file unionfind.hpp.

◆ unionfind_get_set_size()

static uint32_t cv::aruco::unionfind_get_set_size ( unionfind_t uf,
uint32_t  id 
)
inlinestatic

Definition at line 95 of file unionfind.hpp.

◆ zmaxheap_add()

void cv::aruco::zmaxheap_add ( zmaxheap_t heap,
void *  p,
float  v 
)

Definition at line 113 of file zmaxheap.cpp.

◆ zmaxheap_create()

zmaxheap_t * cv::aruco::zmaxheap_create ( size_t  el_sz)

Definition at line 71 of file zmaxheap.cpp.

◆ zmaxheap_destroy()

void cv::aruco::zmaxheap_destroy ( zmaxheap_t heap)

Definition at line 84 of file zmaxheap.cpp.

◆ zmaxheap_remove_index()

static int cv::aruco::zmaxheap_remove_index ( zmaxheap_t heap,
int  idx,
void *  p,
float *  v 
)
static

Definition at line 141 of file zmaxheap.cpp.

◆ zmaxheap_remove_max()

int cv::aruco::zmaxheap_remove_max ( zmaxheap_t heap,
void *  p,
float *  v 
)

Definition at line 203 of file zmaxheap.cpp.

Variable Documentation

◆ DICT_4X4_1000_DATA

const Dictionary cv::aruco::DICT_4X4_1000_DATA = Dictionary(Mat(1000, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 0)

Definition at line 278 of file dictionary.cpp.

◆ DICT_4X4_100_DATA

const Dictionary cv::aruco::DICT_4X4_100_DATA = Dictionary(Mat(100, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 1)

Definition at line 276 of file dictionary.cpp.

◆ DICT_4X4_250_DATA

const Dictionary cv::aruco::DICT_4X4_250_DATA = Dictionary(Mat(250, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 1)

Definition at line 277 of file dictionary.cpp.

◆ DICT_4X4_50_DATA

const Dictionary cv::aruco::DICT_4X4_50_DATA = Dictionary(Mat(50, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_4X4_1000_BYTES), 4, 1)

Definition at line 275 of file dictionary.cpp.

◆ DICT_5X5_1000_DATA

const Dictionary cv::aruco::DICT_5X5_1000_DATA = Dictionary(Mat(1000, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 2)

Definition at line 283 of file dictionary.cpp.

◆ DICT_5X5_100_DATA

const Dictionary cv::aruco::DICT_5X5_100_DATA = Dictionary(Mat(100, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 3)

Definition at line 281 of file dictionary.cpp.

◆ DICT_5X5_250_DATA

const Dictionary cv::aruco::DICT_5X5_250_DATA = Dictionary(Mat(250, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 2)

Definition at line 282 of file dictionary.cpp.

◆ DICT_5X5_50_DATA

const Dictionary cv::aruco::DICT_5X5_50_DATA = Dictionary(Mat(50, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_5X5_1000_BYTES), 5, 3)

Definition at line 280 of file dictionary.cpp.

◆ DICT_6X6_1000_DATA

const Dictionary cv::aruco::DICT_6X6_1000_DATA = Dictionary(Mat(1000, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 4)

Definition at line 288 of file dictionary.cpp.

◆ DICT_6X6_100_DATA

const Dictionary cv::aruco::DICT_6X6_100_DATA = Dictionary(Mat(100, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 5)

Definition at line 286 of file dictionary.cpp.

◆ DICT_6X6_250_DATA

const Dictionary cv::aruco::DICT_6X6_250_DATA = Dictionary(Mat(250, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 5)

Definition at line 287 of file dictionary.cpp.

◆ DICT_6X6_50_DATA

const Dictionary cv::aruco::DICT_6X6_50_DATA = Dictionary(Mat(50, (6*6 + 7)/8 ,CV_8UC4, (uchar*)DICT_6X6_1000_BYTES), 6, 6)

Definition at line 285 of file dictionary.cpp.

◆ DICT_7X7_1000_DATA

const Dictionary cv::aruco::DICT_7X7_1000_DATA = Dictionary(Mat(1000, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 6)

Definition at line 293 of file dictionary.cpp.

◆ DICT_7X7_100_DATA

const Dictionary cv::aruco::DICT_7X7_100_DATA = Dictionary(Mat(100, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 8)

Definition at line 291 of file dictionary.cpp.

◆ DICT_7X7_250_DATA

const Dictionary cv::aruco::DICT_7X7_250_DATA = Dictionary(Mat(250, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 8)

Definition at line 292 of file dictionary.cpp.

◆ DICT_7X7_50_DATA

const Dictionary cv::aruco::DICT_7X7_50_DATA = Dictionary(Mat(50, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 9)

Definition at line 290 of file dictionary.cpp.

◆ DICT_APRILTAG_16h5_DATA

const Dictionary cv::aruco::DICT_APRILTAG_16h5_DATA = Dictionary(Mat(30, (4*4 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_16h5_BYTES), 4, 0)

Definition at line 295 of file dictionary.cpp.

◆ DICT_APRILTAG_25h9_DATA

const Dictionary cv::aruco::DICT_APRILTAG_25h9_DATA = Dictionary(Mat(35, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_25h9_BYTES), 5, 0)

Definition at line 296 of file dictionary.cpp.

◆ DICT_APRILTAG_36h10_DATA

const Dictionary cv::aruco::DICT_APRILTAG_36h10_DATA = Dictionary(Mat(2320, (6*6 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_36h10_BYTES), 6, 0)

Definition at line 297 of file dictionary.cpp.

◆ DICT_APRILTAG_36h11_DATA

const Dictionary cv::aruco::DICT_APRILTAG_36h11_DATA = Dictionary(Mat(587, (6*6 + 7)/8, CV_8UC4, (uchar*)DICT_APRILTAG_36h11_BYTES), 6, 0)

Definition at line 298 of file dictionary.cpp.

◆ DICT_ARUCO_DATA

const Dictionary cv::aruco::DICT_ARUCO_DATA = Dictionary(Mat(1024, (5*5 + 7)/8, CV_8UC4, (uchar*)DICT_ARUCO_BYTES), 5, 0)

Definition at line 273 of file dictionary.cpp.



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