mirror of
https://github.com/opencv/opencv_contrib.git
synced 2025-10-19 11:21:39 +08:00
remove Ptr DetectorParameters
This commit is contained in:
@@ -81,7 +81,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
std::pair<Mat, vector<Point2f> > getProjectMarker(int id, double yaw, double pitch,
|
std::pair<Mat, vector<Point2f> > getProjectMarker(int id, double yaw, double pitch,
|
||||||
const Ptr<aruco::DetectorParameters>& parameters,
|
const aruco::DetectorParameters& parameters,
|
||||||
const Ptr<aruco::Dictionary>& dictionary)
|
const Ptr<aruco::Dictionary>& dictionary)
|
||||||
{
|
{
|
||||||
auto marker_corners = std::make_pair(Mat(imgMarkerSize, imgMarkerSize, CV_8UC1, Scalar::all(255)), vector<Point2f>());
|
auto marker_corners = std::make_pair(Mat(imgMarkerSize, imgMarkerSize, CV_8UC1, Scalar::all(255)), vector<Point2f>());
|
||||||
@@ -90,7 +90,7 @@ public:
|
|||||||
|
|
||||||
// canonical image
|
// canonical image
|
||||||
const int markerSizePixels = static_cast<int>(imgMarkerSize/sqrt(2.f));
|
const int markerSizePixels = static_cast<int>(imgMarkerSize/sqrt(2.f));
|
||||||
aruco::drawMarker(dictionary, id, markerSizePixels, img, parameters->markerBorderBits);
|
aruco::drawMarker(dictionary, id, markerSizePixels, img, parameters.markerBorderBits);
|
||||||
|
|
||||||
// get rvec and tvec for the perspective
|
// get rvec and tvec for the perspective
|
||||||
const double distance = 0.1;
|
const double distance = 0.1;
|
||||||
@@ -123,7 +123,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
std::pair<Mat, map<int, vector<Point2f> > > getProjectMarkersTile(const int numMarkers,
|
std::pair<Mat, map<int, vector<Point2f> > > getProjectMarkersTile(const int numMarkers,
|
||||||
const Ptr<aruco::DetectorParameters>& params,
|
const aruco::DetectorParameters& params,
|
||||||
const Ptr<aruco::Dictionary>& dictionary)
|
const Ptr<aruco::Dictionary>& dictionary)
|
||||||
{
|
{
|
||||||
Mat tileImage(imgMarkerSize*numMarkers, imgMarkerSize*numMarkers, CV_8UC1, Scalar::all(255));
|
Mat tileImage(imgMarkerSize*numMarkers, imgMarkerSize*numMarkers, CV_8UC1, Scalar::all(255));
|
||||||
@@ -178,18 +178,18 @@ PERF_TEST_P(EstimateAruco, ArucoFirst, ESTIMATE_PARAMS)
|
|||||||
{
|
{
|
||||||
UseArucoParams testParams = GetParam();
|
UseArucoParams testParams = GetParam();
|
||||||
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
detectorParams->minDistanceToBorder = 1;
|
detectorParams.minDistanceToBorder = 1;
|
||||||
detectorParams->markerBorderBits = 1;
|
detectorParams.markerBorderBits = 1;
|
||||||
detectorParams->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
|
detectorParams.cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
|
||||||
|
|
||||||
const int markerSize = 100;
|
const int markerSize = 100;
|
||||||
const int numMarkersInRow = 9;
|
const int numMarkersInRow = 9;
|
||||||
//USE_ARUCO3
|
//USE_ARUCO3
|
||||||
detectorParams->useAruco3Detection = get<0>(testParams);
|
detectorParams.useAruco3Detection = get<0>(testParams);
|
||||||
if (detectorParams->useAruco3Detection) {
|
if (detectorParams.useAruco3Detection) {
|
||||||
detectorParams->minSideLengthCanonicalImg = 32;
|
detectorParams.minSideLengthCanonicalImg = 32;
|
||||||
detectorParams->minMarkerLengthRatioOriginalImg = 0.04f / numMarkersInRow;
|
detectorParams.minMarkerLengthRatioOriginalImg = 0.04f / numMarkersInRow;
|
||||||
}
|
}
|
||||||
aruco::ArucoDetector detector(dictionary, detectorParams);
|
aruco::ArucoDetector detector(dictionary, detectorParams);
|
||||||
MarkerPainter painter(markerSize);
|
MarkerPainter painter(markerSize);
|
||||||
@@ -212,16 +212,16 @@ PERF_TEST_P(EstimateAruco, ArucoSecond, ESTIMATE_PARAMS)
|
|||||||
{
|
{
|
||||||
UseArucoParams testParams = GetParam();
|
UseArucoParams testParams = GetParam();
|
||||||
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
detectorParams->minDistanceToBorder = 1;
|
detectorParams.minDistanceToBorder = 1;
|
||||||
detectorParams->markerBorderBits = 1;
|
detectorParams.markerBorderBits = 1;
|
||||||
detectorParams->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
|
detectorParams.cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
|
||||||
|
|
||||||
//USE_ARUCO3
|
//USE_ARUCO3
|
||||||
detectorParams->useAruco3Detection = get<0>(testParams);
|
detectorParams.useAruco3Detection = get<0>(testParams);
|
||||||
if (detectorParams->useAruco3Detection) {
|
if (detectorParams.useAruco3Detection) {
|
||||||
detectorParams->minSideLengthCanonicalImg = 64;
|
detectorParams.minSideLengthCanonicalImg = 64;
|
||||||
detectorParams->minMarkerLengthRatioOriginalImg = 0.f;
|
detectorParams.minMarkerLengthRatioOriginalImg = 0.f;
|
||||||
}
|
}
|
||||||
aruco::ArucoDetector detector(dictionary, detectorParams);
|
aruco::ArucoDetector detector(dictionary, detectorParams);
|
||||||
const int markerSize = 200;
|
const int markerSize = 200;
|
||||||
@@ -268,16 +268,16 @@ PERF_TEST_P(EstimateLargeAruco, ArucoFHD, ESTIMATE_FHD_PARAMS)
|
|||||||
{
|
{
|
||||||
ArucoTestParams testParams = GetParam();
|
ArucoTestParams testParams = GetParam();
|
||||||
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
detectorParams->minDistanceToBorder = 1;
|
detectorParams.minDistanceToBorder = 1;
|
||||||
detectorParams->markerBorderBits = 1;
|
detectorParams.markerBorderBits = 1;
|
||||||
detectorParams->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
|
detectorParams.cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
|
||||||
|
|
||||||
//USE_ARUCO3
|
//USE_ARUCO3
|
||||||
detectorParams->useAruco3Detection = get<0>(testParams).useAruco3Detection;
|
detectorParams.useAruco3Detection = get<0>(testParams).useAruco3Detection;
|
||||||
if (detectorParams->useAruco3Detection) {
|
if (detectorParams.useAruco3Detection) {
|
||||||
detectorParams->minSideLengthCanonicalImg = get<0>(testParams).minSideLengthCanonicalImg;
|
detectorParams.minSideLengthCanonicalImg = get<0>(testParams).minSideLengthCanonicalImg;
|
||||||
detectorParams->minMarkerLengthRatioOriginalImg = get<0>(testParams).minMarkerLengthRatioOriginalImg;
|
detectorParams.minMarkerLengthRatioOriginalImg = get<0>(testParams).minMarkerLengthRatioOriginalImg;
|
||||||
}
|
}
|
||||||
aruco::ArucoDetector detector(dictionary, detectorParams);
|
aruco::ArucoDetector detector(dictionary, detectorParams);
|
||||||
const int markerSize = get<1>(testParams).first; // 1440 or 480 or 144
|
const int markerSize = get<1>(testParams).first; // 1440 or 480 or 144
|
||||||
|
@@ -102,10 +102,10 @@ int main(int argc, char *argv[]) {
|
|||||||
if(parser.get<bool>("zt")) calibrationFlags |= CALIB_ZERO_TANGENT_DIST;
|
if(parser.get<bool>("zt")) calibrationFlags |= CALIB_ZERO_TANGENT_DIST;
|
||||||
if(parser.get<bool>("pc")) calibrationFlags |= CALIB_FIX_PRINCIPAL_POINT;
|
if(parser.get<bool>("pc")) calibrationFlags |= CALIB_FIX_PRINCIPAL_POINT;
|
||||||
|
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
if(parser.has("dp")) {
|
if(parser.has("dp")) {
|
||||||
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
|
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
|
||||||
bool readOk = detectorParams->readDetectorParameters(fs.root());
|
bool readOk = detectorParams.readDetectorParameters(fs.root());
|
||||||
if(!readOk) {
|
if(!readOk) {
|
||||||
cerr << "Invalid detector parameters file" << endl;
|
cerr << "Invalid detector parameters file" << endl;
|
||||||
return 0;
|
return 0;
|
||||||
|
@@ -97,16 +97,16 @@ int main(int argc, char *argv[]) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
if(parser.has("dp")) {
|
if(parser.has("dp")) {
|
||||||
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
|
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
|
||||||
bool readOk = detectorParams->readDetectorParameters(fs.root());
|
bool readOk = detectorParams.readDetectorParameters(fs.root());
|
||||||
if(!readOk) {
|
if(!readOk) {
|
||||||
cerr << "Invalid detector parameters file" << endl;
|
cerr << "Invalid detector parameters file" << endl;
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX; // do corner refinement in markers
|
detectorParams.cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX; // do corner refinement in markers
|
||||||
|
|
||||||
String video;
|
String video;
|
||||||
if(parser.has("v")) {
|
if(parser.has("v")) {
|
||||||
|
@@ -80,10 +80,10 @@ int main(int argc, char *argv[]) {
|
|||||||
bool estimatePose = parser.has("c");
|
bool estimatePose = parser.has("c");
|
||||||
float markerLength = parser.get<float>("l");
|
float markerLength = parser.get<float>("l");
|
||||||
|
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
if(parser.has("dp")) {
|
if(parser.has("dp")) {
|
||||||
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
|
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
|
||||||
bool readOk = detectorParams->readDetectorParameters(fs.root());
|
bool readOk = detectorParams.readDetectorParameters(fs.root());
|
||||||
if(!readOk) {
|
if(!readOk) {
|
||||||
cerr << "Invalid detector parameters file" << endl;
|
cerr << "Invalid detector parameters file" << endl;
|
||||||
return 0;
|
return 0;
|
||||||
@@ -92,9 +92,9 @@ int main(int argc, char *argv[]) {
|
|||||||
|
|
||||||
if (parser.has("refine")) {
|
if (parser.has("refine")) {
|
||||||
//override cornerRefinementMethod read from config file
|
//override cornerRefinementMethod read from config file
|
||||||
detectorParams->cornerRefinementMethod = parser.get<int>("refine");
|
detectorParams.cornerRefinementMethod = parser.get<int>("refine");
|
||||||
}
|
}
|
||||||
std::cout << "Corner refinement method (0: None, 1: Subpixel, 2:contour, 3: AprilTag 2): " << detectorParams->cornerRefinementMethod << std::endl;
|
std::cout << "Corner refinement method (0: None, 1: Subpixel, 2:contour, 3: AprilTag 2): " << detectorParams.cornerRefinementMethod << std::endl;
|
||||||
|
|
||||||
int camId = parser.get<int>("ci");
|
int camId = parser.get<int>("ci");
|
||||||
|
|
||||||
|
@@ -14,7 +14,7 @@ using namespace std;
|
|||||||
void detectMarkers(InputArray _image, const Ptr<Dictionary> &_dictionary, OutputArrayOfArrays _corners,
|
void detectMarkers(InputArray _image, const Ptr<Dictionary> &_dictionary, OutputArrayOfArrays _corners,
|
||||||
OutputArray _ids, const Ptr<DetectorParameters> &_params,
|
OutputArray _ids, const Ptr<DetectorParameters> &_params,
|
||||||
OutputArrayOfArrays _rejectedImgPoints) {
|
OutputArrayOfArrays _rejectedImgPoints) {
|
||||||
ArucoDetector detector(_dictionary, _params);
|
ArucoDetector detector(_dictionary, *_params);
|
||||||
detector.detectMarkers(_image, _corners, _ids, _rejectedImgPoints);
|
detector.detectMarkers(_image, _corners, _ids, _rejectedImgPoints);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -25,7 +25,7 @@ void refineDetectedMarkers(InputArray _image, const Ptr<Board> &_board,
|
|||||||
bool checkAllOrders, OutputArray _recoveredIdxs,
|
bool checkAllOrders, OutputArray _recoveredIdxs,
|
||||||
const Ptr<DetectorParameters> &_params) {
|
const Ptr<DetectorParameters> &_params) {
|
||||||
RefineParameters refineParams(minRepDistance, errorCorrectionRate, checkAllOrders);
|
RefineParameters refineParams(minRepDistance, errorCorrectionRate, checkAllOrders);
|
||||||
ArucoDetector detector(_board->getDictionary(), _params, refineParams);
|
ArucoDetector detector(_board->getDictionary(), *_params, refineParams);
|
||||||
detector.refineDetectedMarkers(_image, _board, _detectedCorners, _detectedIds, _rejectedCorners, _cameraMatrix,
|
detector.refineDetectedMarkers(_image, _board, _detectedCorners, _detectedIds, _rejectedCorners, _cameraMatrix,
|
||||||
_distCoeffs, _recoveredIdxs);
|
_distCoeffs, _recoveredIdxs);
|
||||||
}
|
}
|
||||||
|
@@ -90,7 +90,7 @@ static int _selectAndRefineChessboardCorners(InputArray _allCorners, InputArray
|
|||||||
else
|
else
|
||||||
grey = _image.getMat();
|
grey = _image.getMat();
|
||||||
|
|
||||||
const Ptr<DetectorParameters> params = makePtr<aruco::DetectorParameters>(); // use default params for corner refinement
|
DetectorParameters params; // use default params for corner refinement
|
||||||
|
|
||||||
//// For each of the charuco corners, apply subpixel refinement using its correspondind winSize
|
//// For each of the charuco corners, apply subpixel refinement using its correspondind winSize
|
||||||
parallel_for_(Range(0, (int)filteredChessboardImgPoints.size()), [&](const Range& range) {
|
parallel_for_(Range(0, (int)filteredChessboardImgPoints.size()), [&](const Range& range) {
|
||||||
@@ -102,12 +102,12 @@ static int _selectAndRefineChessboardCorners(InputArray _allCorners, InputArray
|
|||||||
in.push_back(filteredChessboardImgPoints[i] - Point2f(0.5, 0.5)); // adjust sub-pixel coordinates for cornerSubPix
|
in.push_back(filteredChessboardImgPoints[i] - Point2f(0.5, 0.5)); // adjust sub-pixel coordinates for cornerSubPix
|
||||||
Size winSize = filteredWinSizes[i];
|
Size winSize = filteredWinSizes[i];
|
||||||
if (winSize.height == -1 || winSize.width == -1)
|
if (winSize.height == -1 || winSize.width == -1)
|
||||||
winSize = Size(params->cornerRefinementWinSize, params->cornerRefinementWinSize);
|
winSize = Size(params.cornerRefinementWinSize, params.cornerRefinementWinSize);
|
||||||
|
|
||||||
cornerSubPix(grey, in, winSize, Size(),
|
cornerSubPix(grey, in, winSize, Size(),
|
||||||
TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
|
TermCriteria(TermCriteria::MAX_ITER | TermCriteria::EPS,
|
||||||
params->cornerRefinementMaxIterations,
|
params.cornerRefinementMaxIterations,
|
||||||
params->cornerRefinementMinAccuracy));
|
params.cornerRefinementMinAccuracy));
|
||||||
|
|
||||||
filteredChessboardImgPoints[i] = in[0] + Point2f(0.5, 0.5);
|
filteredChessboardImgPoints[i] = in[0] + Point2f(0.5, 0.5);
|
||||||
}
|
}
|
||||||
@@ -428,7 +428,7 @@ void detectCharucoDiamond(InputArray _image, InputArrayOfArrays _markerCorners,
|
|||||||
// try to find the rest of markers in the diamond
|
// try to find the rest of markers in the diamond
|
||||||
vector< int > acceptedIdxs;
|
vector< int > acceptedIdxs;
|
||||||
RefineParameters refineParameters(minRepDistance, -1.f, false);
|
RefineParameters refineParameters(minRepDistance, -1.f, false);
|
||||||
ArucoDetector detector(dictionary, makePtr<DetectorParameters>(), refineParameters);
|
ArucoDetector detector(dictionary, DetectorParameters(), refineParameters);
|
||||||
detector.refineDetectedMarkers(grey, _charucoDiamondLayout, currentMarker, currentMarkerId, candidates,
|
detector.refineDetectedMarkers(grey, _charucoDiamondLayout, currentMarker, currentMarkerId, candidates,
|
||||||
noArray(), noArray(), acceptedIdxs);
|
noArray(), noArray(), acceptedIdxs);
|
||||||
|
|
||||||
|
@@ -51,7 +51,7 @@ TEST(CV_ArucoTutorial, can_find_gboriginal)
|
|||||||
|
|
||||||
FileStorage fs(dictPath, FileStorage::READ);
|
FileStorage fs(dictPath, FileStorage::READ);
|
||||||
dictionary->aruco::Dictionary::readDictionary(fs.root()); // set marker from tutorial_dict.yml
|
dictionary->aruco::Dictionary::readDictionary(fs.root()); // set marker from tutorial_dict.yml
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
|
|
||||||
aruco::ArucoDetector detector(dictionary, detectorParams);
|
aruco::ArucoDetector detector(dictionary, detectorParams);
|
||||||
|
|
||||||
@@ -186,9 +186,9 @@ TEST(CV_ArucoTutorial, can_find_diamondmarkers)
|
|||||||
|
|
||||||
string detectorPath = cvtest::findDataFile("detector_params.yml", false);
|
string detectorPath = cvtest::findDataFile("detector_params.yml", false);
|
||||||
fs = FileStorage(detectorPath, FileStorage::READ);
|
fs = FileStorage(detectorPath, FileStorage::READ);
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
detectorParams->readDetectorParameters(fs.root());
|
detectorParams.readDetectorParameters(fs.root());
|
||||||
detectorParams->cornerRefinementMethod = 3;
|
detectorParams.cornerRefinementMethod = 3;
|
||||||
|
|
||||||
aruco::ArucoDetector detector(dictionary, detectorParams);
|
aruco::ArucoDetector detector(dictionary, detectorParams);
|
||||||
|
|
||||||
|
@@ -55,15 +55,14 @@ class CV_ArucoBoardPose : public cvtest::BaseTest {
|
|||||||
public:
|
public:
|
||||||
CV_ArucoBoardPose(ArucoAlgParams arucoAlgParams)
|
CV_ArucoBoardPose(ArucoAlgParams arucoAlgParams)
|
||||||
{
|
{
|
||||||
Ptr<aruco::DetectorParameters> params;
|
aruco::DetectorParameters params;
|
||||||
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
||||||
params = makePtr<aruco::DetectorParameters>();
|
params.minDistanceToBorder = 3;
|
||||||
params->minDistanceToBorder = 3;
|
|
||||||
if (arucoAlgParams == ArucoAlgParams::USE_ARUCO3) {
|
if (arucoAlgParams == ArucoAlgParams::USE_ARUCO3) {
|
||||||
params->useAruco3Detection = true;
|
params.useAruco3Detection = true;
|
||||||
params->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
|
params.cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
|
||||||
params->minSideLengthCanonicalImg = 16;
|
params.minSideLengthCanonicalImg = 16;
|
||||||
params->errorCorrectionRate = 0.8;
|
params.errorCorrectionRate = 0.8;
|
||||||
}
|
}
|
||||||
detector = aruco::ArucoDetector(dictionary, params);
|
detector = aruco::ArucoDetector(dictionary, params);
|
||||||
}
|
}
|
||||||
@@ -99,7 +98,7 @@ void CV_ArucoBoardPose::run(int) {
|
|||||||
imgSize, markerBorder);
|
imgSize, markerBorder);
|
||||||
vector<vector<Point2f> > corners;
|
vector<vector<Point2f> > corners;
|
||||||
vector<int> ids;
|
vector<int> ids;
|
||||||
detector.getDetectorParameters()->markerBorderBits = markerBorder;
|
detector.getDetectorParameters().markerBorderBits = markerBorder;
|
||||||
detector.detectMarkers(img, corners, ids);
|
detector.detectMarkers(img, corners, ids);
|
||||||
|
|
||||||
ASSERT_EQ(ids.size(), gridboard->getIds().size());
|
ASSERT_EQ(ids.size(), gridboard->getIds().size());
|
||||||
@@ -165,11 +164,11 @@ class CV_ArucoRefine : public cvtest::BaseTest {
|
|||||||
CV_ArucoRefine(ArucoAlgParams arucoAlgParams)
|
CV_ArucoRefine(ArucoAlgParams arucoAlgParams)
|
||||||
{
|
{
|
||||||
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
|
||||||
Ptr<aruco::DetectorParameters> params = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters params;
|
||||||
params->minDistanceToBorder = 3;
|
params.minDistanceToBorder = 3;
|
||||||
params->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
|
params.cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
|
||||||
if (arucoAlgParams == ArucoAlgParams::USE_ARUCO3)
|
if (arucoAlgParams == ArucoAlgParams::USE_ARUCO3)
|
||||||
params->useAruco3Detection = true;
|
params.useAruco3Detection = true;
|
||||||
aruco::RefineParameters refineParams(10.f, 3.f, true);
|
aruco::RefineParameters refineParams(10.f, 3.f, true);
|
||||||
detector = aruco::ArucoDetector(dictionary, params, refineParams);
|
detector = aruco::ArucoDetector(dictionary, params, refineParams);
|
||||||
}
|
}
|
||||||
@@ -208,7 +207,7 @@ void CV_ArucoRefine::run(int) {
|
|||||||
// detect markers
|
// detect markers
|
||||||
vector<vector<Point2f> > corners, rejected;
|
vector<vector<Point2f> > corners, rejected;
|
||||||
vector<int> ids;
|
vector<int> ids;
|
||||||
detector.getDetectorParameters()->markerBorderBits = markerBorder;
|
detector.getDetectorParameters().markerBorderBits = markerBorder;
|
||||||
detector.detectMarkers(img, corners, ids, rejected);
|
detector.detectMarkers(img, corners, ids, rejected);
|
||||||
|
|
||||||
// remove a marker from detection
|
// remove a marker from detection
|
||||||
|
@@ -132,8 +132,8 @@ void CV_CharucoDetection::run(int) {
|
|||||||
int iter = 0;
|
int iter = 0;
|
||||||
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
|
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
|
||||||
Size imgSize(500, 500);
|
Size imgSize(500, 500);
|
||||||
Ptr<aruco::DetectorParameters> params = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters params;
|
||||||
params->minDistanceToBorder = 3;
|
params.minDistanceToBorder = 3;
|
||||||
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
|
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
|
||||||
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, detector.getDictionary());
|
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, detector.getDictionary());
|
||||||
|
|
||||||
@@ -160,7 +160,7 @@ void CV_CharucoDetection::run(int) {
|
|||||||
vector<vector<Point2f> > corners;
|
vector<vector<Point2f> > corners;
|
||||||
vector<int> ids;
|
vector<int> ids;
|
||||||
|
|
||||||
detector.getDetectorParameters()->markerBorderBits = markerBorder;
|
detector.getDetectorParameters().markerBorderBits = markerBorder;
|
||||||
detector.detectMarkers(img, corners, ids);
|
detector.detectMarkers(img, corners, ids);
|
||||||
|
|
||||||
if(ids.size() == 0) {
|
if(ids.size() == 0) {
|
||||||
@@ -238,8 +238,8 @@ void CV_CharucoPoseEstimation::run(int) {
|
|||||||
int iter = 0;
|
int iter = 0;
|
||||||
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
|
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
|
||||||
Size imgSize(500, 500);
|
Size imgSize(500, 500);
|
||||||
Ptr<aruco::DetectorParameters> params = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters params;
|
||||||
params->minDistanceToBorder = 3;
|
params.minDistanceToBorder = 3;
|
||||||
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
|
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
|
||||||
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, detector.getDictionary());
|
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, detector.getDictionary());
|
||||||
|
|
||||||
@@ -264,7 +264,7 @@ void CV_CharucoPoseEstimation::run(int) {
|
|||||||
// detect markers
|
// detect markers
|
||||||
vector< vector< Point2f > > corners;
|
vector< vector< Point2f > > corners;
|
||||||
vector< int > ids;
|
vector< int > ids;
|
||||||
detector.getDetectorParameters()->markerBorderBits = markerBorder;
|
detector.getDetectorParameters().markerBorderBits = markerBorder;
|
||||||
detector.detectMarkers(img, corners, ids);
|
detector.detectMarkers(img, corners, ids);
|
||||||
|
|
||||||
ASSERT_EQ(ids.size(), board->getIds().size());
|
ASSERT_EQ(ids.size(), board->getIds().size());
|
||||||
@@ -348,8 +348,8 @@ void CV_CharucoDiamondDetection::run(int) {
|
|||||||
int iter = 0;
|
int iter = 0;
|
||||||
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
|
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
|
||||||
Size imgSize(500, 500);
|
Size imgSize(500, 500);
|
||||||
Ptr<aruco::DetectorParameters> params = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters params ;
|
||||||
params->minDistanceToBorder = 0;
|
params.minDistanceToBorder = 0;
|
||||||
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
|
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_6X6_250), params);
|
||||||
float squareLength = 0.03f;
|
float squareLength = 0.03f;
|
||||||
float markerLength = 0.015f;
|
float markerLength = 0.015f;
|
||||||
@@ -380,7 +380,7 @@ void CV_CharucoDiamondDetection::run(int) {
|
|||||||
// detect markers
|
// detect markers
|
||||||
vector< vector< Point2f > > corners;
|
vector< vector< Point2f > > corners;
|
||||||
vector< int > ids;
|
vector< int > ids;
|
||||||
detector.getDetectorParameters()->markerBorderBits = markerBorder;
|
detector.getDetectorParameters().markerBorderBits = markerBorder;
|
||||||
detector.detectMarkers(img, corners, ids);
|
detector.detectMarkers(img, corners, ids);
|
||||||
|
|
||||||
if(ids.size() != 4) {
|
if(ids.size() != 4) {
|
||||||
@@ -643,8 +643,8 @@ TEST(Charuco, testBoardSubpixelCoords)
|
|||||||
board->draw(Size(res.width, res.height), gray, 150);
|
board->draw(Size(res.width, res.height), gray, 150);
|
||||||
cv::GaussianBlur(gray, gray, Size(5, 5), 1.0);
|
cv::GaussianBlur(gray, gray, Size(5, 5), 1.0);
|
||||||
|
|
||||||
Ptr<aruco::DetectorParameters> params = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters params;
|
||||||
params->cornerRefinementMethod = cv::aruco::CORNER_REFINE_APRILTAG;
|
params.cornerRefinementMethod = cv::aruco::CORNER_REFINE_APRILTAG;
|
||||||
|
|
||||||
aruco::ArucoDetector detector(dict, params);
|
aruco::ArucoDetector detector(dict, params);
|
||||||
|
|
||||||
@@ -674,9 +674,9 @@ TEST(Charuco, issue_14014)
|
|||||||
string imgPath = cvtest::findDataFile("aruco/recover.png");
|
string imgPath = cvtest::findDataFile("aruco/recover.png");
|
||||||
Mat img = imread(imgPath);
|
Mat img = imread(imgPath);
|
||||||
|
|
||||||
Ptr<aruco::DetectorParameters> detectorParams = makePtr<aruco::DetectorParameters>();
|
aruco::DetectorParameters detectorParams;
|
||||||
detectorParams->cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
|
detectorParams.cornerRefinementMethod = aruco::CORNER_REFINE_SUBPIX;
|
||||||
detectorParams->cornerRefinementMinAccuracy = 0.01;
|
detectorParams.cornerRefinementMinAccuracy = 0.01;
|
||||||
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_7X7_250), detectorParams);
|
aruco::ArucoDetector detector(aruco::getPredefinedDictionary(aruco::DICT_7X7_250), detectorParams);
|
||||||
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(8, 5, 0.03455f, 0.02164f, detector.getDictionary());
|
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(8, 5, 0.03455f, 0.02164f, detector.getDictionary());
|
||||||
|
|
||||||
|
Reference in New Issue
Block a user