From a10b39752bb8138cd7fccdb4320dbfdc75717928 Mon Sep 17 00:00:00 2001 From: AleksandrPanov Date: Thu, 17 Mar 2022 20:14:19 +0300 Subject: [PATCH] add writeDictionary(), add dict distance, fix readDictionary(), fix readDetectorParameters() --- modules/aruco/include/opencv2/aruco.hpp | 2 +- .../include/opencv2/aruco/dictionary.hpp | 38 ++++++++-------- modules/aruco/samples/calibrate_camera.cpp | 6 +-- .../samples/calibrate_camera_charuco.cpp | 6 +-- modules/aruco/samples/create_board.cpp | 4 +- .../aruco/samples/create_board_charuco.cpp | 4 +- modules/aruco/samples/create_marker.cpp | 4 +- modules/aruco/samples/detect_board.cpp | 6 +-- .../aruco/samples/detect_board_charuco.cpp | 6 +-- modules/aruco/samples/detect_diamonds.cpp | 6 +-- modules/aruco/samples/detect_markers.cpp | 6 +-- modules/aruco/src/aruco.cpp | 44 +++++++++---------- modules/aruco/src/dictionary.cpp | 33 +++++++++++--- modules/aruco/test/test_arucodetection.cpp | 2 +- modules/aruco/test/test_charucodetection.cpp | 8 ++-- 15 files changed, 97 insertions(+), 78 deletions(-) diff --git a/modules/aruco/include/opencv2/aruco.hpp b/modules/aruco/include/opencv2/aruco.hpp index 99d31794b93..91d57cef27e 100644 --- a/modules/aruco/include/opencv2/aruco.hpp +++ b/modules/aruco/include/opencv2/aruco.hpp @@ -151,7 +151,7 @@ struct CV_EXPORTS_W DetectorParameters { DetectorParameters(); CV_WRAP static Ptr create(); - CV_WRAP static bool readDetectorParameters(const FileNode& fn, Ptr& params); + CV_WRAP bool readDetectorParameters(const FileNode& fn); CV_PROP_RW int adaptiveThreshWinSizeMin; CV_PROP_RW int adaptiveThreshWinSizeMax; diff --git a/modules/aruco/include/opencv2/aruco/dictionary.hpp b/modules/aruco/include/opencv2/aruco/dictionary.hpp index 27374d8f53b..197fd2026cf 100644 --- a/modules/aruco/include/opencv2/aruco/dictionary.hpp +++ b/modules/aruco/include/opencv2/aruco/dictionary.hpp @@ -101,7 +101,9 @@ class CV_EXPORTS_W Dictionary { * ... * marker_34: "011111010000111011111110110101100101" */ - CV_WRAP static bool readDictionary(const cv::FileNode& fn, cv::Ptr &dictionary); + CV_WRAP bool readDictionary(const cv::FileNode& fn); + + CV_WRAP void writeDictionary(const String& outputDictFile); /** * @see getPredefinedDictionary @@ -149,23 +151,23 @@ class CV_EXPORTS_W Dictionary { distance */ enum PREDEFINED_DICTIONARY_NAME { - DICT_4X4_50 = 0, - DICT_4X4_100, - DICT_4X4_250, - DICT_4X4_1000, - DICT_5X5_50, - DICT_5X5_100, - DICT_5X5_250, - DICT_5X5_1000, - DICT_6X6_50, - DICT_6X6_100, - DICT_6X6_250, - DICT_6X6_1000, - DICT_7X7_50, - DICT_7X7_100, - DICT_7X7_250, - DICT_7X7_1000, - DICT_ARUCO_ORIGINAL, + DICT_4X4_50 = 0, ///< 4x4 bits, minimum hamming distance between any two codes = 4, 50 codes + DICT_4X4_100, ///< 4x4 bits, minimum hamming distance between any two codes = 3, 100 codes + DICT_4X4_250, ///< 4x4 bits, minimum hamming distance between any two codes = 3, 250 codes + DICT_4X4_1000, ///< 4x4 bits, minimum hamming distance between any two codes = 2, 1000 codes + DICT_5X5_50, ///< 5x5 bits, minimum hamming distance between any two codes = 8, 50 codes + DICT_5X5_100, ///< 5x5 bits, minimum hamming distance between any two codes = 7, 100 codes + DICT_5X5_250, ///< 5x5 bits, minimum hamming distance between any two codes = 6, 250 codes + DICT_5X5_1000, ///< 5x5 bits, minimum hamming distance between any two codes = 5, 1000 codes + DICT_6X6_50, ///< 6x6 bits, minimum hamming distance between any two codes = 13, 50 codes + DICT_6X6_100, ///< 6x6 bits, minimum hamming distance between any two codes = 12, 100 codes + DICT_6X6_250, ///< 6x6 bits, minimum hamming distance between any two codes = 11, 250 codes + DICT_6X6_1000, ///< 6x6 bits, minimum hamming distance between any two codes = 9, 1000 codes + DICT_7X7_50, ///< 7x7 bits, minimum hamming distance between any two codes = 19, 50 codes + DICT_7X7_100, ///< 7x7 bits, minimum hamming distance between any two codes = 18, 100 codes + DICT_7X7_250, ///< 7x7 bits, minimum hamming distance between any two codes = 17, 250 codes + DICT_7X7_1000, ///< 7x7 bits, minimum hamming distance between any two codes = 14, 1000 codes + DICT_ARUCO_ORIGINAL, ///< 6x6 bits, minimum hamming distance between any two codes = 3, 1024 codes DICT_APRILTAG_16h5, ///< 4x4 bits, minimum hamming distance between any two codes = 5, 30 codes DICT_APRILTAG_25h9, ///< 5x5 bits, minimum hamming distance between any two codes = 9, 35 codes DICT_APRILTAG_36h10, ///< 6x6 bits, minimum hamming distance between any two codes = 10, 2320 codes diff --git a/modules/aruco/samples/calibrate_camera.cpp b/modules/aruco/samples/calibrate_camera.cpp index 3162ae7ca29..a52bab5b161 100644 --- a/modules/aruco/samples/calibrate_camera.cpp +++ b/modules/aruco/samples/calibrate_camera.cpp @@ -104,7 +104,7 @@ int main(int argc, char *argv[]) { Ptr detectorParams = aruco::DetectorParameters::create(); if(parser.has("dp")) { FileStorage fs(parser.get("dp"), FileStorage::READ); - bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams); + bool readOk = detectorParams->readDetectorParameters(fs.root()); if(!readOk) { cerr << "Invalid detector parameters file" << endl; return 0; @@ -134,14 +134,14 @@ int main(int argc, char *argv[]) { waitTime = 10; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { cerr << "Invalid dictionary file" << endl; return 0; diff --git a/modules/aruco/samples/calibrate_camera_charuco.cpp b/modules/aruco/samples/calibrate_camera_charuco.cpp index 112f9059773..57b09bd96f0 100644 --- a/modules/aruco/samples/calibrate_camera_charuco.cpp +++ b/modules/aruco/samples/calibrate_camera_charuco.cpp @@ -105,7 +105,7 @@ int main(int argc, char *argv[]) { Ptr detectorParams = aruco::DetectorParameters::create(); if(parser.has("dp")) { FileStorage fs(parser.get("dp"), FileStorage::READ); - bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams); + bool readOk = detectorParams->readDetectorParameters(fs.root()); if(!readOk) { cerr << "Invalid detector parameters file" << endl; return 0; @@ -135,14 +135,14 @@ int main(int argc, char *argv[]) { waitTime = 10; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { cerr << "Invalid dictionary file" << endl; return 0; diff --git a/modules/aruco/samples/create_board.cpp b/modules/aruco/samples/create_board.cpp index a11eeda38f1..d2482bce853 100644 --- a/modules/aruco/samples/create_board.cpp +++ b/modules/aruco/samples/create_board.cpp @@ -96,14 +96,14 @@ int main(int argc, char *argv[]) { imageSize.height = markersY * (markerLength + markerSeparation) - markerSeparation + 2 * margins; - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { std::cerr << "Invalid dictionary file" << std::endl; diff --git a/modules/aruco/samples/create_board_charuco.cpp b/modules/aruco/samples/create_board_charuco.cpp index 7c8c4ba1fe3..29afb1b5fb5 100644 --- a/modules/aruco/samples/create_board_charuco.cpp +++ b/modules/aruco/samples/create_board_charuco.cpp @@ -93,14 +93,14 @@ int main(int argc, char *argv[]) { return 0; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0);;; if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { std::cerr << "Invalid dictionary file" << std::endl; return 0; diff --git a/modules/aruco/samples/create_marker.cpp b/modules/aruco/samples/create_marker.cpp index a3b2172960b..fe31ec2972f 100644 --- a/modules/aruco/samples/create_marker.cpp +++ b/modules/aruco/samples/create_marker.cpp @@ -84,14 +84,14 @@ int main(int argc, char *argv[]) { return 0; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { std::cerr << "Invalid dictionary file" << std::endl; return 0; diff --git a/modules/aruco/samples/detect_board.cpp b/modules/aruco/samples/detect_board.cpp index 0534a5e80ee..883be8dd2e3 100644 --- a/modules/aruco/samples/detect_board.cpp +++ b/modules/aruco/samples/detect_board.cpp @@ -100,7 +100,7 @@ int main(int argc, char *argv[]) { Ptr detectorParams = aruco::DetectorParameters::create(); if(parser.has("dp")) { FileStorage fs(parser.get("dp"), FileStorage::READ); - bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams); + bool readOk = detectorParams->readDetectorParameters(fs.root()); if(!readOk) { cerr << "Invalid detector parameters file" << endl; return 0; @@ -118,14 +118,14 @@ int main(int argc, char *argv[]) { return 0; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { cerr << "Invalid dictionary file" << endl; return 0; diff --git a/modules/aruco/samples/detect_board_charuco.cpp b/modules/aruco/samples/detect_board_charuco.cpp index a6336377078..f413cef9fb3 100644 --- a/modules/aruco/samples/detect_board_charuco.cpp +++ b/modules/aruco/samples/detect_board_charuco.cpp @@ -102,7 +102,7 @@ int main(int argc, char *argv[]) { Ptr detectorParams = aruco::DetectorParameters::create(); if(parser.has("dp")) { FileStorage fs(parser.get("dp"), FileStorage::READ); - bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams); + bool readOk = detectorParams->readDetectorParameters(fs.root()); if(!readOk) { cerr << "Invalid detector parameters file" << endl; return 0; @@ -114,14 +114,14 @@ int main(int argc, char *argv[]) { return 0; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { cerr << "Invalid dictionary file" << endl; return 0; diff --git a/modules/aruco/samples/detect_diamonds.cpp b/modules/aruco/samples/detect_diamonds.cpp index bd8aa51d9eb..e5255a6602c 100644 --- a/modules/aruco/samples/detect_diamonds.cpp +++ b/modules/aruco/samples/detect_diamonds.cpp @@ -90,7 +90,7 @@ int main(int argc, char *argv[]) { Ptr detectorParams = aruco::DetectorParameters::create(); if(parser.has("dp")) { FileStorage fs(parser.get("dp"), FileStorage::READ); - bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams); + bool readOk = detectorParams->readDetectorParameters(fs.root()); if(!readOk) { cerr << "Invalid detector parameters file" << endl; return 0; @@ -114,14 +114,14 @@ int main(int argc, char *argv[]) { return 0; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { cerr << "Invalid dictionary file" << endl; return 0; diff --git a/modules/aruco/samples/detect_markers.cpp b/modules/aruco/samples/detect_markers.cpp index 5085a346ee5..f7d17b9f8a8 100644 --- a/modules/aruco/samples/detect_markers.cpp +++ b/modules/aruco/samples/detect_markers.cpp @@ -83,7 +83,7 @@ int main(int argc, char *argv[]) { Ptr detectorParams = aruco::DetectorParameters::create(); if(parser.has("dp")) { FileStorage fs(parser.get("dp"), FileStorage::READ); - bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams); + bool readOk = detectorParams->readDetectorParameters(fs.root()); if(!readOk) { cerr << "Invalid detector parameters file" << endl; return 0; @@ -108,14 +108,14 @@ int main(int argc, char *argv[]) { return 0; } - Ptr dictionary; + Ptr dictionary = aruco::getPredefinedDictionary(0); if (parser.has("d")) { int dictionaryId = parser.get("d"); dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId)); } else if (parser.has("cd")) { FileStorage fs(parser.get("cd"), FileStorage::READ); - bool readOk = aruco::Dictionary::readDictionary(fs.root(), dictionary); + bool readOk = dictionary->aruco::Dictionary::readDictionary(fs.root()); if(!readOk) { std::cerr << "Invalid dictionary file" << std::endl; return 0; diff --git a/modules/aruco/src/aruco.cpp b/modules/aruco/src/aruco.cpp index 4c8ca4e7f50..9ebd3171e64 100644 --- a/modules/aruco/src/aruco.cpp +++ b/modules/aruco/src/aruco.cpp @@ -111,32 +111,31 @@ static inline bool readParameter(const FileNode& node, T& parameter) /** * @brief Read a new set of DetectorParameters from FileStorage. */ -bool DetectorParameters::readDetectorParameters(const FileNode& fn, Ptr& params) +bool DetectorParameters::readDetectorParameters(const FileNode& fn) { if(fn.empty()) return true; - params = DetectorParameters::create(); bool checkRead = false; - checkRead |= readParameter(fn["adaptiveThreshWinSizeMin"], params->adaptiveThreshWinSizeMin); - checkRead |= readParameter(fn["adaptiveThreshWinSizeMax"], params->adaptiveThreshWinSizeMax); - checkRead |= readParameter(fn["adaptiveThreshWinSizeStep"], params->adaptiveThreshWinSizeStep); - checkRead |= readParameter(fn["adaptiveThreshConstant"], params->adaptiveThreshConstant); - checkRead |= readParameter(fn["minMarkerPerimeterRate"], params->minMarkerPerimeterRate); - checkRead |= readParameter(fn["maxMarkerPerimeterRate"], params->maxMarkerPerimeterRate); - checkRead |= readParameter(fn["polygonalApproxAccuracyRate"], params->polygonalApproxAccuracyRate); - checkRead |= readParameter(fn["minCornerDistanceRate"], params->minCornerDistanceRate); - checkRead |= readParameter(fn["minDistanceToBorder"], params->minDistanceToBorder); - checkRead |= readParameter(fn["minMarkerDistanceRate"], params->minMarkerDistanceRate); - checkRead |= readParameter(fn["cornerRefinementMethod"], params->cornerRefinementMethod); - checkRead |= readParameter(fn["cornerRefinementWinSize"], params->cornerRefinementWinSize); - checkRead |= readParameter(fn["cornerRefinementMaxIterations"], params->cornerRefinementMaxIterations); - checkRead |= readParameter(fn["cornerRefinementMinAccuracy"], params->cornerRefinementMinAccuracy); - checkRead |= readParameter(fn["markerBorderBits"], params->markerBorderBits); - checkRead |= readParameter(fn["perspectiveRemovePixelPerCell"], params->perspectiveRemovePixelPerCell); - checkRead |= readParameter(fn["perspectiveRemoveIgnoredMarginPerCell"], params->perspectiveRemoveIgnoredMarginPerCell); - checkRead |= readParameter(fn["maxErroneousBitsInBorderRate"], params->maxErroneousBitsInBorderRate); - checkRead |= readParameter(fn["minOtsuStdDev"], params->minOtsuStdDev); - checkRead |= readParameter(fn["errorCorrectionRate"], params->errorCorrectionRate); + checkRead |= readParameter(fn["adaptiveThreshWinSizeMin"], this->adaptiveThreshWinSizeMin); + checkRead |= readParameter(fn["adaptiveThreshWinSizeMax"], this->adaptiveThreshWinSizeMax); + checkRead |= readParameter(fn["adaptiveThreshWinSizeStep"], this->adaptiveThreshWinSizeStep); + checkRead |= readParameter(fn["adaptiveThreshConstant"], this->adaptiveThreshConstant); + checkRead |= readParameter(fn["minMarkerPerimeterRate"], this->minMarkerPerimeterRate); + checkRead |= readParameter(fn["maxMarkerPerimeterRate"], this->maxMarkerPerimeterRate); + checkRead |= readParameter(fn["polygonalApproxAccuracyRate"], this->polygonalApproxAccuracyRate); + checkRead |= readParameter(fn["minCornerDistanceRate"], this->minCornerDistanceRate); + checkRead |= readParameter(fn["minDistanceToBorder"], this->minDistanceToBorder); + checkRead |= readParameter(fn["minMarkerDistanceRate"], this->minMarkerDistanceRate); + checkRead |= readParameter(fn["cornerRefinementMethod"], this->cornerRefinementMethod); + checkRead |= readParameter(fn["cornerRefinementWinSize"], this->cornerRefinementWinSize); + checkRead |= readParameter(fn["cornerRefinementMaxIterations"], this->cornerRefinementMaxIterations); + checkRead |= readParameter(fn["cornerRefinementMinAccuracy"], this->cornerRefinementMinAccuracy); + checkRead |= readParameter(fn["markerBorderBits"], this->markerBorderBits); + checkRead |= readParameter(fn["perspectiveRemovePixelPerCell"], this->perspectiveRemovePixelPerCell); + checkRead |= readParameter(fn["perspectiveRemoveIgnoredMarginPerCell"], this->perspectiveRemoveIgnoredMarginPerCell); + checkRead |= readParameter(fn["maxErroneousBitsInBorderRate"], this->maxErroneousBitsInBorderRate); + checkRead |= readParameter(fn["minOtsuStdDev"], this->minOtsuStdDev); + checkRead |= readParameter(fn["errorCorrectionRate"], this->errorCorrectionRate); return checkRead; } @@ -305,7 +304,6 @@ static void _filterTooCloseCandidates(const vector< vector< Point2f > > &candida // if mean square distance is too low, remove the smaller one of the two markers double minMarkerDistancePixels = double(minimumPerimeter) * minMarkerDistanceRate; if(distSq < minMarkerDistancePixels * minMarkerDistancePixels) { - // i and j are not related to a group if(candGroup[i]<0 && candGroup[j]<0){ // mark candidates with their corresponding group number diff --git a/modules/aruco/src/dictionary.cpp b/modules/aruco/src/dictionary.cpp index 75431da4f7c..9ad45ef792f 100644 --- a/modules/aruco/src/dictionary.cpp +++ b/modules/aruco/src/dictionary.cpp @@ -94,27 +94,46 @@ static inline bool readParameter(const FileNode& node, T& parameter) return false; } -bool Dictionary::readDictionary(const cv::FileNode& fn, cv::Ptr &dictionary) +bool Dictionary::readDictionary(const cv::FileNode& fn) { - int nMarkers = 0, markerSize = 0; - if(fn.empty() || !readParameter(fn["nmarkers"], nMarkers) || !readParameter(fn["markersize"], markerSize)) + int nMarkers = 0, _markerSize = 0; + if (fn.empty() || !readParameter(fn["nmarkers"], nMarkers) || !readParameter(fn["markersize"], _markerSize)) return false; - cv::Mat bytes(0, 0, CV_8UC1), marker(markerSize, markerSize, CV_8UC1); + Mat bytes(0, 0, CV_8UC1), marker(_markerSize, _markerSize, CV_8UC1); std::string markerString; for (int i = 0; i < nMarkers; i++) { std::ostringstream ostr; ostr << i; if (!readParameter(fn["marker_" + ostr.str()], markerString)) return false; - for (int j = 0; j < (int) markerString.size(); j++) marker.at(j) = (markerString[j] == '0') ? 0 : 1; - bytes.push_back(cv::aruco::Dictionary::getByteListFromBits(marker)); + bytes.push_back(Dictionary::getByteListFromBits(marker)); } - dictionary = cv::makePtr(bytes, markerSize); + int _maxCorrectionBits = 0; + readParameter(fn["maxCorrectionBits"], _maxCorrectionBits); + *this = Dictionary(bytes, _markerSize, _maxCorrectionBits); return true; } +void Dictionary::writeDictionary(const String& outputDictFile) { + FileStorage fs(outputDictFile, FileStorage::WRITE); + fs << "nmarkers" << bytesList.rows; + fs << "markersize" << markerSize; + fs << "maxCorrectionBits" << maxCorrectionBits; + for (int i = 0; i < bytesList.rows; i++) { + Mat row = bytesList.row(i);; + Mat bitMarker = getBitsFromByteList(row, markerSize); + std::ostringstream ostr; + ostr << i; + string markerName = "marker_" + ostr.str(); + string marker; + for (int j = 0; j < markerSize * markerSize; j++) + marker.push_back(bitMarker.at(j) + '0'); + fs << markerName << marker; + } +} + /** */ Ptr Dictionary::get(int dict) { diff --git a/modules/aruco/test/test_arucodetection.cpp b/modules/aruco/test/test_arucodetection.cpp index 7219a542bf2..47aaa2502cd 100644 --- a/modules/aruco/test/test_arucodetection.cpp +++ b/modules/aruco/test/test_arucodetection.cpp @@ -597,7 +597,7 @@ TEST(CV_ArucoTutorial, can_find_gboriginal) cv::Ptr dictionary; FileStorage fs(dictPath, FileStorage::READ); - aruco::Dictionary::readDictionary(fs.root(), dictionary); // set marker from tutorial_dict.yml + dictionary->aruco::Dictionary::readDictionary(fs.root()); // set marker from tutorial_dict.yml Ptr detectorParams = aruco::DetectorParameters::create(); diff --git a/modules/aruco/test/test_charucodetection.cpp b/modules/aruco/test/test_charucodetection.cpp index f539122b26b..9a404b14b82 100644 --- a/modules/aruco/test/test_charucodetection.cpp +++ b/modules/aruco/test/test_charucodetection.cpp @@ -695,14 +695,14 @@ TEST(CV_ArucoTutorial, can_find_diamondmarkers) Mat image = imread(imgPath); string dictPath = cvtest::findDataFile("tutorial_dict.yml", false); - cv::Ptr dictionary; + Ptr dictionary; FileStorage fs(dictPath, FileStorage::READ); - aruco::Dictionary::readDictionary(fs.root(), dictionary); // set marker from tutorial_dict.yml + dictionary->aruco::Dictionary::readDictionary(fs.root()); // set marker from tutorial_dict.yml string detectorPath = cvtest::findDataFile("detector_params.yml", false); fs = FileStorage(detectorPath, FileStorage::READ); - Ptr detectorParams; - aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams); + Ptr detectorParams = aruco::DetectorParameters::create(); + detectorParams->readDetectorParameters(fs.root()); detectorParams->cornerRefinementMethod = 3; vector< int > ids;