Skip to content

Commit

Permalink
remove camParams and add cornerIndex check
Browse files Browse the repository at this point in the history
(cherry picked from commit ef980e7)
  • Loading branch information
AleksandrPanov committed Mar 24, 2022
1 parent 1490611 commit 1d0115a
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 37 deletions.
10 changes: 4 additions & 6 deletions modules/aruco/include/opencv2/aruco.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,21 +230,19 @@ struct CV_EXPORTS_W DetectorParameters {
* @param parameters marker detection parameters
* @param rejectedImgPoints contains the imgPoints of those squares whose inner code has not a
* correct codification. Useful for debugging purposes.
* @param cameraMatrix optional input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeff optional vector of distortion coefficients
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
*
* Performs marker detection in the input image. Only markers included in the specific dictionary
* are searched. For each detected marker, it returns the 2D position of its corner in the image
* and its corresponding identifier.
* Note that this function does not perform pose estimation.
* @sa estimatePoseSingleMarkers, estimatePoseBoard
* @note The function does not correct lens distortion or takes it into account. It's recommended to undistort
* input image with corresponging camera model, if camera parameters are known
* @sa undistort, estimatePoseSingleMarkers, estimatePoseBoard
*
*/
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());
OutputArrayOfArrays rejectedImgPoints = noArray());



Expand Down
37 changes: 7 additions & 30 deletions modules/aruco/src/aruco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -797,6 +797,7 @@ static void _getSingleMarkerObjectPoints(float markerLength, OutputArray _objPoi
* @param nContours, contour-container
*/
static Point3f _interpolate2Dline(const std::vector<cv::Point2f>& nContours){
CV_Assert(nContours.size() >= 2);
float minX, minY, maxX, maxY;
minX = maxX = nContours[0].x;
minY = maxY = nContours[0].y;
Expand Down Expand Up @@ -847,35 +848,15 @@ static Point2f _getCrossPoint(Point3f nLine1, Point3f nLine2){
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){
static void _refineCandidateLines(std::vector<Point>& nContours, std::vector<Point2f>& nCorners){
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
Expand All @@ -893,10 +874,10 @@ static void _refineCandidateLines(std::vector<Point>& nContours, std::vector<Poi
}
cntPts[group].push_back(contour2f[i]);
}

for (int i = 0; i < 4; i++)
CV_Assert(cornerIndex[i] != -1);
// saves extra group into corresponding
if( !cntPts[4].empty() ){
CV_CheckLT(group, 4, "FIXIT: avoiding infinite loop: implementation should be revised: https://github.com/opencv/opencv_contrib/issues/2738");
for( unsigned int i=0; i < cntPts[4].size() ; i++ )
cntPts[group].push_back(cntPts[4].at(i));
cntPts[4].clear();
Expand Down Expand Up @@ -929,12 +910,9 @@ static void _refineCandidateLines(std::vector<Point>& nContours, std::vector<Poi
else
nCorners[i] = _getCrossPoint(lines[ i ], lines[ (i+3)%4 ]); // 30 01 12 23
}

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


#ifdef APRIL_DEBUG
static void _darken(const Mat &im){
for (int y = 0; y < im.rows; y++) {
Expand Down Expand Up @@ -1093,7 +1071,7 @@ static inline void findCornerInPyrImage(const float scale_init, const int closes
*/
void detectMarkers(InputArray _image, const Ptr<Dictionary> &_dictionary, OutputArrayOfArrays _corners,
OutputArray _ids, const Ptr<DetectorParameters> &_params,
OutputArrayOfArrays _rejectedImgPoints, InputArrayOfArrays camMatrix, InputArrayOfArrays distCoeff) {
OutputArrayOfArrays _rejectedImgPoints) {

CV_Assert(!_image.empty());
CV_Assert(_params->markerBorderBits > 0);
Expand Down Expand Up @@ -1205,8 +1183,7 @@ void detectMarkers(InputArray _image, const Ptr<Dictionary> &_dictionary, Output
// do corner refinement using the contours for each detected markers
parallel_for_(Range(0, _corners.cols()), [&](const Range& range) {
for (int i = range.start; i < range.end; i++) {
_refineCandidateLines(contours[i], candidates[i], camMatrix.getMat(),
distCoeff.getMat());
_refineCandidateLines(contours[i], candidates[i]);
}
});

Expand Down
2 changes: 1 addition & 1 deletion modules/aruco/test/test_charucodetection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -713,7 +713,7 @@ TEST(Charuco, testBoardSubpixelCoords)
std::vector<int> ids;
std::vector<std::vector<cv::Point2f>> corners, rejected;

cv::aruco::detectMarkers(gray, dict, corners, ids, params, rejected, K);
cv::aruco::detectMarkers(gray, dict, corners, ids, params, rejected);

ASSERT_EQ(ids.size(), size_t(8));

Expand Down

0 comments on commit 1d0115a

Please sign in to comment.