Skip to content

Commit

Permalink
update tests and samples to class API
Browse files Browse the repository at this point in the history
  • Loading branch information
AleksandrPanov committed May 4, 2022
1 parent d4792f3 commit 5bd62f7
Show file tree
Hide file tree
Showing 18 changed files with 172 additions and 167 deletions.
1 change: 1 addition & 0 deletions modules/aruco/include/opencv2/aruco.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ the use of this software, even if advised of the possibility of such damage.
#define __OPENCV_ARUCO_HPP__

#include "opencv2/aruco_detector.hpp"
#include "opencv2/aruco/aruco_calib_pose.hpp"

/**
* @defgroup aruco ArUco Marker Detection
Expand Down
46 changes: 43 additions & 3 deletions modules/aruco/include/opencv2/aruco_detector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,48 @@ enum CornerRefineMethod{
* The parameter tau_i has a direct influence on the processing speed.
*/
struct CV_EXPORTS_W DetectorParameters {
DetectorParameters();
CV_WRAP static Ptr<DetectorParameters> create();
DetectorParameters():
adaptiveThreshWinSizeMin(3),
adaptiveThreshWinSizeMax(23),
adaptiveThreshWinSizeStep(10),
adaptiveThreshConstant(7),
minMarkerPerimeterRate(0.03),
maxMarkerPerimeterRate(4.),
polygonalApproxAccuracyRate(0.03),
minCornerDistanceRate(0.05),
minDistanceToBorder(3),
minMarkerDistanceRate(0.05),
cornerRefinementMethod(CORNER_REFINE_NONE),
cornerRefinementWinSize(5),
cornerRefinementMaxIterations(30),
cornerRefinementMinAccuracy(0.1),
markerBorderBits(1),
perspectiveRemovePixelPerCell(4),
perspectiveRemoveIgnoredMarginPerCell(0.13),
maxErroneousBitsInBorderRate(0.35),
minOtsuStdDev(5.0),
errorCorrectionRate(0.6),
aprilTagQuadDecimate(0.0),
aprilTagQuadSigma(0.0),
aprilTagMinClusterPixels(5),
aprilTagMaxNmaxima(10),
aprilTagCriticalRad( (float)(10* CV_PI /180) ),
aprilTagMaxLineFitMse(10.0),
aprilTagMinWhiteBlackDiff(5),
aprilTagDeglitch(0),
detectInvertedMarker(false),
useAruco3Detection(false),
minSideLengthCanonicalImg(32),
minMarkerLengthRatioOriginalImg(0.0) {};

/**
* @brief Create a new set of DetectorParameters with default values.
*/
CV_WRAP static Ptr<DetectorParameters> create() {
Ptr<DetectorParameters> params = makePtr<DetectorParameters>();
return params;
}

CV_WRAP bool readDetectorParameters(const FileNode& fn);

CV_PROP_RW int adaptiveThreshWinSizeMin;
Expand Down Expand Up @@ -145,6 +185,7 @@ struct CV_EXPORTS_W DetectorParameters {
CV_PROP_RW bool useAruco3Detection;
CV_PROP_RW int minSideLengthCanonicalImg;
CV_PROP_RW float minMarkerLengthRatioOriginalImg;

};

struct CV_EXPORTS_W RefineParameters {
Expand Down Expand Up @@ -285,7 +326,6 @@ CV_EXPORTS_W void drawDetectedMarkers(InputOutputArray image, InputArrayOfArrays
*/
CV_EXPORTS_W void drawMarker(const Ptr<Dictionary> &dictionary, int id, int sidePixels, OutputArray img,
int borderBits = 1);
//};

//! @}

Expand Down
9 changes: 6 additions & 3 deletions modules/aruco/perf/perf_aruco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,7 @@ PERF_TEST_P(EstimateAruco, ArucoFirst, ESTIMATE_PARAMS)
detectorParams->minSideLengthCanonicalImg = 32;
detectorParams->minMarkerLengthRatioOriginalImg = 0.04f / numMarkersInRow;
}
aruco::ArucoDetector detector(dictionary, detectorParams);
MarkerPainter painter(markerSize);
auto image_map = painter.getProjectMarkersTile(numMarkersInRow, detectorParams, dictionary);

Expand All @@ -198,7 +199,7 @@ PERF_TEST_P(EstimateAruco, ArucoFirst, ESTIMATE_PARAMS)
vector<int> ids;
TEST_CYCLE()
{
aruco::detectMarkers(image_map.first, dictionary, corners, ids, detectorParams);
detector.detectMarkers(image_map.first, corners, ids);
}
ASSERT_EQ(numMarkersInRow*numMarkersInRow, static_cast<int>(ids.size()));
double maxDistance = getMaxDistance(image_map.second, ids, corners);
Expand All @@ -221,6 +222,7 @@ PERF_TEST_P(EstimateAruco, ArucoSecond, ESTIMATE_PARAMS)
detectorParams->minSideLengthCanonicalImg = 64;
detectorParams->minMarkerLengthRatioOriginalImg = 0.f;
}
aruco::ArucoDetector detector(dictionary, detectorParams);
const int markerSize = 200;
const int numMarkersInRow = 11;
MarkerPainter painter(markerSize);
Expand All @@ -231,7 +233,7 @@ PERF_TEST_P(EstimateAruco, ArucoSecond, ESTIMATE_PARAMS)
vector<int> ids;
TEST_CYCLE()
{
aruco::detectMarkers(image_map.first, dictionary, corners, ids, detectorParams);
detector.detectMarkers(image_map.first, corners, ids);
}
ASSERT_EQ(numMarkersInRow*numMarkersInRow, static_cast<int>(ids.size()));
double maxDistance = getMaxDistance(image_map.second, ids, corners);
Expand Down Expand Up @@ -276,6 +278,7 @@ PERF_TEST_P(EstimateLargeAruco, ArucoFHD, ESTIMATE_FHD_PARAMS)
detectorParams->minSideLengthCanonicalImg = get<0>(testParams).minSideLengthCanonicalImg;
detectorParams->minMarkerLengthRatioOriginalImg = get<0>(testParams).minMarkerLengthRatioOriginalImg;
}
aruco::ArucoDetector detector(dictionary, detectorParams);
const int markerSize = get<1>(testParams).first; // 1440 or 480 or 144
const int numMarkersInRow = get<1>(testParams).second; // 1 or 3 or 144
MarkerPainter painter(markerSize); // num pixels is 1440x1440 as in FHD 1920x1080
Expand All @@ -286,7 +289,7 @@ PERF_TEST_P(EstimateLargeAruco, ArucoFHD, ESTIMATE_FHD_PARAMS)
vector<int> ids;
TEST_CYCLE()
{
aruco::detectMarkers(image_map.first, dictionary, corners, ids, detectorParams);
detector.detectMarkers(image_map.first, corners, ids);
}
ASSERT_EQ(numMarkersInRow*numMarkersInRow, static_cast<int>(ids.size()));
double maxDistance = getMaxDistance(image_map.second, ids, corners);
Expand Down
2 changes: 1 addition & 1 deletion modules/aruco/perf/perf_precomp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#define __OPENCV_PERF_PRECOMP_HPP__

#include "opencv2/ts.hpp"
#include "opencv2/aruco.hpp"
#include "opencv2/aruco_detector.hpp"
#include "opencv2/calib3d.hpp"

#endif
2 changes: 1 addition & 1 deletion modules/aruco/samples/aruco_dict_utils.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <opencv2/core/hal/hal.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <iostream>

using namespace cv;
Expand Down
2 changes: 1 addition & 1 deletion modules/aruco/samples/aruco_samples_utility.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/calib3d.hpp>
#include <ctime>

Expand Down
9 changes: 6 additions & 3 deletions modules/aruco/samples/calibrate_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ the use of this software, even if advised of the possibility of such damage.

#include <opencv2/highgui.hpp>
#include <opencv2/calib3d.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib_pose.hpp>
#include <opencv2/imgproc.hpp>
#include <vector>
#include <iostream>
Expand Down Expand Up @@ -162,6 +163,8 @@ int main(int argc, char *argv[]) {
vector< vector< int > > allIds;
Size imgSize;

aruco::ArucoDetector detector(dictionary, detectorParams);

while(inputVideo.grab()) {
Mat image, imageCopy;
inputVideo.retrieve(image);
Expand All @@ -170,10 +173,10 @@ int main(int argc, char *argv[]) {
vector< vector< Point2f > > corners, rejected;

// detect markers
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);

// refind strategy to detect more markers
if(refindStrategy) aruco::refineDetectedMarkers(image, board, corners, ids, rejected);
if(refindStrategy) detector.refineDetectedMarkers(image, board, corners, ids, rejected);

// draw results
image.copyTo(imageCopy);
Expand Down
2 changes: 1 addition & 1 deletion modules/aruco/samples/create_board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ the use of this software, even if advised of the possibility of such damage.


#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <iostream>
#include "aruco_samples_utility.hpp"

Expand Down
2 changes: 1 addition & 1 deletion modules/aruco/samples/create_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ the use of this software, even if advised of the possibility of such damage.


#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <iostream>
#include "aruco_samples_utility.hpp"

Expand Down
11 changes: 6 additions & 5 deletions modules/aruco/samples/detect_board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ the use of this software, even if advised of the possibility of such damage.


#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib_pose.hpp>
#include <vector>
#include <iostream>
#include "aruco_samples_utility.hpp"
Expand Down Expand Up @@ -135,7 +136,7 @@ int main(int argc, char *argv[]) {
cerr << "Dictionary not specified" << endl;
return 0;
}

aruco::ArucoDetector detector(dictionary, detectorParams);
VideoCapture inputVideo;
int waitTime;
if(!video.empty()) {
Expand Down Expand Up @@ -168,12 +169,12 @@ int main(int argc, char *argv[]) {
Vec3d rvec, tvec;

// detect markers
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);

// refind strategy to detect more markers
if(refindStrategy)
aruco::refineDetectedMarkers(image, board, corners, ids, rejected, camMatrix,
distCoeffs);
detector.refineDetectedMarkers(image, board, corners, ids, rejected, camMatrix,
distCoeffs);

// estimate board pose
int markersOfBoardDetected = 0;
Expand Down
7 changes: 4 additions & 3 deletions modules/aruco/samples/detect_markers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,8 @@ the use of this software, even if advised of the possibility of such damage.


#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/aruco_detector.hpp>
#include <opencv2/aruco/aruco_calib_pose.hpp>
#include <iostream>
#include "aruco_samples_utility.hpp"

Expand Down Expand Up @@ -134,7 +135,7 @@ int main(int argc, char *argv[]) {
return 0;
}
}

aruco::ArucoDetector detector(dictionary, detectorParams);
VideoCapture inputVideo;
int waitTime;
if(!video.empty()) {
Expand All @@ -159,7 +160,7 @@ int main(int argc, char *argv[]) {
vector< Vec3d > rvecs, tvecs;

// detect markers and estimate pose
aruco::detectMarkers(image, dictionary, corners, ids, detectorParams, rejected);
detector.detectMarkers(image, corners, ids, rejected);
if(estimatePose && ids.size() > 0)
aruco::estimatePoseSingleMarkers(corners, markerLength, camMatrix, distCoeffs, rvecs,
tvecs);
Expand Down
2 changes: 1 addition & 1 deletion modules/aruco/src/apriltag/apriltag_quad_thresh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#define _OPENCV_APRIL_QUAD_THRESH_HPP_

#include <opencv2/imgproc.hpp>
#include "opencv2/aruco.hpp"
#include "opencv2/aruco_detector.hpp"
#include "unionfind.hpp"
#include "zmaxheap.hpp"
#include "zarray.hpp"
Expand Down
52 changes: 3 additions & 49 deletions modules/aruco/src/aruco_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,50 +15,6 @@ namespace aruco {

using namespace std;

DetectorParameters::DetectorParameters()
: adaptiveThreshWinSizeMin(3),
adaptiveThreshWinSizeMax(23),
adaptiveThreshWinSizeStep(10),
adaptiveThreshConstant(7),
minMarkerPerimeterRate(0.03),
maxMarkerPerimeterRate(4.),
polygonalApproxAccuracyRate(0.03),
minCornerDistanceRate(0.05),
minDistanceToBorder(3),
minMarkerDistanceRate(0.05),
cornerRefinementMethod(CORNER_REFINE_NONE),
cornerRefinementWinSize(5),
cornerRefinementMaxIterations(30),
cornerRefinementMinAccuracy(0.1),
markerBorderBits(1),
perspectiveRemovePixelPerCell(4),
perspectiveRemoveIgnoredMarginPerCell(0.13),
maxErroneousBitsInBorderRate(0.35),
minOtsuStdDev(5.0),
errorCorrectionRate(0.6),
aprilTagQuadDecimate(0.0),
aprilTagQuadSigma(0.0),
aprilTagMinClusterPixels(5),
aprilTagMaxNmaxima(10),
aprilTagCriticalRad( (float)(10* CV_PI /180) ),
aprilTagMaxLineFitMse(10.0),
aprilTagMinWhiteBlackDiff(5),
aprilTagDeglitch(0),
detectInvertedMarker(false),
useAruco3Detection(false),
minSideLengthCanonicalImg(32),
minMarkerLengthRatioOriginalImg(0.0)
{}


/**
* @brief Create a new set of DetectorParameters with default values.
*/
Ptr<DetectorParameters> DetectorParameters::create() {
Ptr<DetectorParameters> params = makePtr<DetectorParameters>();
return params;
}

template<typename T>
static inline bool readParameter(const FileNode& node, T& parameter)
{
Expand Down Expand Up @@ -832,7 +788,6 @@ static inline void findCornerInPyrImage(const float scale_init, const int closes
*/
void ArucoDetector::detectMarkers(InputArray _image, OutputArrayOfArrays _corners, OutputArray _ids,
OutputArrayOfArrays _rejectedImgPoints) {

CV_Assert(!_image.empty());
CV_Assert(params->markerBorderBits > 0);
// check that the parameters are set correctly if Aruco3 is used
Expand Down Expand Up @@ -991,9 +946,8 @@ void ArucoDetector::refineDetectedMarkers(InputArray _image, const Ptr<Board> &_
vector< bool > alreadyIdentified(_rejectedCorners.total(), false);

// maximum bits that can be corrected
Dictionary &dictionary = *(_board->dictionary);
int maxCorrectionRecalculated =
int(double(dictionary.maxCorrectionBits) * refineParams->errorCorrectionRate);
int(double(dictionary->maxCorrectionBits) * refineParams->errorCorrectionRate);

Mat grey;
_convertToGrey(_image, grey);
Expand Down Expand Up @@ -1061,7 +1015,7 @@ void ArucoDetector::refineDetectedMarkers(InputArray _image, const Ptr<Board> &_

// extract bits
Mat bits = _extractBits(
grey, rotatedMarker, dictionary.markerSize, params->markerBorderBits,
grey, rotatedMarker, dictionary->markerSize, params->markerBorderBits,
params->perspectiveRemovePixelPerCell,
params->perspectiveRemoveIgnoredMarginPerCell, params->minOtsuStdDev);

Expand All @@ -1070,7 +1024,7 @@ void ArucoDetector::refineDetectedMarkers(InputArray _image, const Ptr<Board> &_
.colRange(params->markerBorderBits, bits.rows - params->markerBorderBits);

codeDistance =
dictionary.getDistanceToId(onlyBits, undetectedMarkersIds[i], false);
dictionary->getDistanceToId(onlyBits, undetectedMarkersIds[i], false);
}

// if everythin is ok, assign values to current best match
Expand Down
Loading

0 comments on commit 5bd62f7

Please sign in to comment.