|
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 void | cv::aruco::_convertToGrey (InputArray _in, OutputArray _out) |
| Convert input image to gray if it is a 3-channels image. More...
|
|
static void | cv::aruco::_copyVector2Output (vector< vector< Point2f > > &vec, OutputArrayOfArrays out) |
| Copy the contents of a corners vector to an OutputArray, settings its size. More...
|
|
static void | cv::aruco::_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 | cv::aruco::_detectInitialCandidates (const Mat &grey, vector< vector< Point2f > > &candidates, vector< vector< Point > > &contours, const Ptr< DetectorParameters > ¶ms) |
| Initial steps on finding square candidates. More...
|
|
static void | cv::aruco::_distortPoints (vector< cv::Point2f > &in, const Mat &camMatrix, const Mat &distCoeff) |
|
void | cv::aruco::_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 | cv::aruco::_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 void | cv::aruco::_filterDetectedMarkers (vector< vector< Point2f > > &_corners, vector< int > &_ids, vector< vector< Point > > &_contours) |
| Final filter of markers after its identification. More...
|
|
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) |
| Check candidates that are too close to each other and remove the smaller one. More...
|
|
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) |
| Given a tresholded image, find the contours, calculate their polygonal approximation and take those that accomplish some conditions. More...
|
|
static int | cv::aruco::_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 | cv::aruco::_getCrossPoint (Point3f nLine1, Point3f nLine2) |
|
static void | cv::aruco::_getSingleMarkerObjectPoints (float markerLength, OutputArray _objPoints) |
| Return object points for the system centered in a single marker, given the marker length. More...
|
|
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 > ¶ms, OutputArrayOfArrays _rejected=noArray()) |
| Identify square candidates according to a marker dictionary. More...
|
|
static bool | cv::aruco::_identifyOneCandidate (const Ptr< Dictionary > &dictionary, InputArray _image, vector< Point2f > &_corners, int &idx, const Ptr< DetectorParameters > ¶ms) |
| Tries to identify one candidate given the dictionary. More...
|
|
static Point3f | cv::aruco::_interpolate2Dline (const std::vector< cv::Point2f > &nContours) |
|
static void | cv::aruco::_projectUndetectedMarkers (const Ptr< Board > &_board, InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds, InputArray _cameraMatrix, InputArray _distCoeffs, vector< vector< Point2f > > &_undetectedMarkersProjectedCorners, OutputArray _undetectedMarkersIds) |
|
static void | cv::aruco::_projectUndetectedMarkers (const Ptr< Board > &_board, InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds, vector< vector< Point2f > > &_undetectedMarkersProjectedCorners, OutputArray _undetectedMarkersIds) |
|
static void | cv::aruco::_refineCandidateLines (std::vector< Point > &nContours, std::vector< Point2f > &nCorners, const Mat &camMatrix, const Mat &distCoeff) |
|
static void | cv::aruco::_reorderCandidatesCorners (vector< vector< Point2f > > &candidates) |
| Assure order of candidate corners is clockwise direction. More...
|
|
static void | cv::aruco::_threshold (InputArray _in, OutputArray _out, int winSize, double constant) |
| Threshold input image using adaptive thresholding. More...
|
|
CV_EXPORTS_W double | cv::aruco::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 | 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) |
|
void | cv::aruco::detectMarkers (InputArray _image, const Ptr< Dictionary > &_dictionary, OutputArrayOfArrays _corners, OutputArray _ids, const Ptr< DetectorParameters > &_params, OutputArrayOfArrays _rejectedImgPoints, InputArrayOfArrays camMatrix, InputArrayOfArrays distCoeff) |
|
CV_EXPORTS_W void | cv::aruco::drawAxis (InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs, InputArray rvec, InputArray tvec, float length) |
| Draw coordinate system axis from pose estimation. More...
|
|
CV_EXPORTS_W void | cv::aruco::drawDetectedMarkers (InputOutputArray image, InputArrayOfArrays corners, InputArray ids=noArray(), Scalar borderColor=Scalar(0, 255, 0)) |
| Draw detected markers in image. More...
|
|
CV_EXPORTS_W void | cv::aruco::drawMarker (const Ptr< Dictionary > &dictionary, int id, int sidePixels, OutputArray img, int borderBits=1) |
| Draw a canonical marker image. More...
|
|
CV_EXPORTS_W void | cv::aruco::drawPlanarBoard (const Ptr< Board > &board, Size outSize, OutputArray img, int marginSize=0, int borderBits=1) |
| Draw a planar board. More...
|
|
CV_EXPORTS_W int | cv::aruco::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 void | cv::aruco::estimatePoseSingleMarkers (InputArrayOfArrays corners, float markerLength, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvecs, OutputArray tvecs, OutputArray _objPoints=noArray()) |
| Pose estimation for single markers. More...
|
|
CV_EXPORTS_W void | cv::aruco::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_W void | cv::aruco::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. More...
|
|