39 #ifndef __OPENCV_ARUCO_HPP__ 40 #define __OPENCV_ARUCO_HPP__ 42 #include <opencv2/core.hpp> 154 CV_WRAP
static Ptr<DetectorParameters> create();
221 CV_EXPORTS_W
void detectMarkers(InputArray image,
const Ptr<Dictionary> &dictionary, OutputArrayOfArrays corners,
223 OutputArrayOfArrays rejectedImgPoints = noArray(), InputArray
cameraMatrix= noArray(), InputArray distCoeff= noArray());
258 OutputArray
rvecs, OutputArray
tvecs, OutputArray _objPoints = noArray());
283 CV_WRAP
static Ptr<Board> create(InputArrayOfArrays objPoints,
const Ptr<Dictionary> &dictionary, InputArray ids);
286 CV_PROP std::vector< std::vector< Point3f > >
objPoints;
293 CV_PROP std::vector< int >
ids;
317 CV_WRAP
void draw(Size outSize, OutputArray img,
int marginSize = 0,
int borderBits = 1);
334 CV_WRAP
static Ptr<GridBoard> create(
int markersX,
int markersY,
float markerLength,
335 float markerSeparation,
const Ptr<Dictionary> &dictionary,
int firstMarker = 0);
340 CV_WRAP Size
getGridSize()
const {
return Size(_markersX, _markersY); }
395 InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec,
396 OutputArray tvec,
bool useExtrinsicGuess =
false);
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,
459 InputArray ids = noArray(),
460 Scalar borderColor = Scalar(0, 255, 0));
482 CV_EXPORTS_W
void drawAxis(InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs,
483 InputArray rvec, InputArray tvec,
float length);
499 CV_EXPORTS_W
void drawMarker(
const Ptr<Dictionary> &dictionary,
int id,
int sidePixels, OutputArray img,
519 CV_EXPORTS_W
void drawPlanarBoard(
const Ptr<Board> &board, Size outSize, OutputArray img,
520 int marginSize = 0,
int borderBits = 1);
528 int marginSize = 0,
int borderBits = 1);
569 InputArrayOfArrays corners, InputArray ids, InputArray
counter,
const Ptr<Board> &board,
570 Size
imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
571 OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
574 TermCriteria
criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
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));
597 InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints);
CV_PROP_RW double polygonalApproxAccuracyRate
CV_EXPORTS_AS(calibrateCameraCharucoExtended) double calibrateCameraCharuco(InputArrayOfArrays charucoCorners
Calibrate a camera using Charuco corners.
CV_PROP_RW double minOtsuStdDev
ArUco approach and refine the corners locations using the contour-points line fitting.
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...
Parameters for the detectMarker process:
InputArray InputArray counter
CV_PROP_RW int perspectiveRemovePixelPerCell
ArUco approach and refine the corners locations using corner subpixel accuracy.
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray cameraMatrix
InputArrayOfArrays const Ptr< CharucoBoard > Size imageSize
CV_WRAP float getMarkerLength() const
CV_PROP_RW int aprilTagMinWhiteBlackDiff
CV_PROP_RW float aprilTagMaxLineFitMse
CV_PROP_RW double minMarkerDistanceRate
CV_PROP_RW int adaptiveThreshWinSizeMin
CV_PROP_RW int aprilTagMinClusterPixels
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray distCoeffs
CV_PROP_RW double adaptiveThreshConstant
CV_PROP_RW int cornerRefinementMaxIterations
Tag and corners detection based on the ArUco approach.
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int TermCriteria criteria
CV_PROP_RW int cornerRefinementMethod
CV_PROP Ptr< Dictionary > dictionary
the dictionary of markers employed for this board
Tag and corners detection based on the AprilTag 2 approach .
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray stdDeviationsExtrinsics
CV_PROP_RW int cornerRefinementWinSize
CV_PROP_RW int aprilTagMaxNmaxima
CV_PROP_RW int adaptiveThreshWinSizeMax
CV_PROP_RW int minDistanceToBorder
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray perViewErrors
CV_PROP_RW float aprilTagQuadDecimate
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray OutputArray OutputArray int flags
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays OutputArray stdDeviationsIntrinsics
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.
CV_PROP_RW double maxMarkerPerimeterRate
CV_PROP std::vector< std::vector< Point3f > > objPoints
void _drawPlanarBoardImpl(Board *board, Size outSize, OutputArray img, int marginSize=0, int borderBits=1)
Implementation of drawPlanarBoard that accepts a raw Board pointer.
CV_PROP_RW double minCornerDistanceRate
CV_PROP_RW bool detectInvertedMarker
CV_PROP_RW int adaptiveThreshWinSizeStep
CV_PROP_RW int markerBorderBits
CV_PROP_RW double cornerRefinementMinAccuracy
CV_PROP_RW double maxErroneousBitsInBorderRate
CV_PROP_RW double minMarkerPerimeterRate
CV_PROP_RW double perspectiveRemoveIgnoredMarginPerCell
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 > ¶meters=DetectorParameters::create())
Refind not detected markers based on the already detected and the board layout.
CV_WRAP float getMarkerSeparation() const
CV_EXPORTS_W void drawMarker(const Ptr< Dictionary > &dictionary, int id, int sidePixels, OutputArray img, int borderBits=1)
Draw a canonical marker image.
CV_EXPORTS_W void drawDetectedMarkers(InputOutputArray image, InputArrayOfArrays corners, InputArray ids=noArray(), Scalar borderColor=Scalar(0, 255, 0))
Draw detected markers in image.
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays rvecs
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.
static CV_WRAP Ptr< DetectorParameters > create()
Create a new set of DetectorParameters with default values.
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.
CV_PROP_RW float aprilTagCriticalRad
Planar board with grid arrangement of markers More common type of board. All markers are placed in th...
CV_PROP_RW double errorCorrectionRate
CV_PROP std::vector< int > ids
CV_PROP_RW int aprilTagDeglitch
CV_WRAP Size getGridSize() const
InputArrayOfArrays const Ptr< CharucoBoard > Size InputOutputArray InputOutputArray OutputArrayOfArrays OutputArrayOfArrays tvecs
CV_EXPORTS_W void detectMarkers(InputArray image, const Ptr< Dictionary > &dictionary, OutputArrayOfArrays corners, OutputArray ids, const Ptr< DetectorParameters > ¶meters=DetectorParameters::create(), OutputArrayOfArrays rejectedImgPoints=noArray(), InputArray cameraMatrix=noArray(), InputArray distCoeff=noArray())
Basic marker detection.
CV_PROP_RW float aprilTagQuadSigma
InputArrayOfArrays const Ptr< CharucoBoard > & board
CV_EXPORTS_W void drawAxis(InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs, InputArray rvec, InputArray tvec, float length)
Draw coordinate system axis from pose estimation.
CV_EXPORTS_W void drawPlanarBoard(const Ptr< Board > &board, Size outSize, OutputArray img, int marginSize=0, int borderBits=1)
Draw a planar board.