Skip to content

Commit

Permalink
add writeDictionary(), add dict distance, fix readDictionary(), fix r…
Browse files Browse the repository at this point in the history
…eadDetectorParameters()
  • Loading branch information
AleksandrPanov committed Mar 17, 2022
1 parent 56d492c commit a10b397
Show file tree
Hide file tree
Showing 15 changed files with 97 additions and 78 deletions.
2 changes: 1 addition & 1 deletion modules/aruco/include/opencv2/aruco.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ struct CV_EXPORTS_W DetectorParameters {

DetectorParameters();
CV_WRAP static Ptr<DetectorParameters> create();
CV_WRAP static bool readDetectorParameters(const FileNode& fn, Ptr<DetectorParameters>& params);
CV_WRAP bool readDetectorParameters(const FileNode& fn);

CV_PROP_RW int adaptiveThreshWinSizeMin;
CV_PROP_RW int adaptiveThreshWinSizeMax;
Expand Down
38 changes: 20 additions & 18 deletions modules/aruco/include/opencv2/aruco/dictionary.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,9 @@ class CV_EXPORTS_W Dictionary {
* ...
* marker_34: "011111010000111011111110110101100101"
*/
CV_WRAP static bool readDictionary(const cv::FileNode& fn, cv::Ptr<cv::aruco::Dictionary> &dictionary);
CV_WRAP bool readDictionary(const cv::FileNode& fn);

CV_WRAP void writeDictionary(const String& outputDictFile);

/**
* @see getPredefinedDictionary
Expand Down Expand Up @@ -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
Expand Down
6 changes: 3 additions & 3 deletions modules/aruco/samples/calibrate_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ int main(int argc, char *argv[]) {
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
FileStorage fs(parser.get<string>("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;
Expand Down Expand Up @@ -134,14 +134,14 @@ int main(int argc, char *argv[]) {
waitTime = 10;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
6 changes: 3 additions & 3 deletions modules/aruco/samples/calibrate_camera_charuco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ int main(int argc, char *argv[]) {
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
FileStorage fs(parser.get<string>("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;
Expand Down Expand Up @@ -135,14 +135,14 @@ int main(int argc, char *argv[]) {
waitTime = 10;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
4 changes: 2 additions & 2 deletions modules/aruco/samples/create_board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,14 +96,14 @@ int main(int argc, char *argv[]) {
imageSize.height =
markersY * (markerLength + markerSeparation) - markerSeparation + 2 * margins;

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
4 changes: 2 additions & 2 deletions modules/aruco/samples/create_board_charuco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,14 +93,14 @@ int main(int argc, char *argv[]) {
return 0;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);;;
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
4 changes: 2 additions & 2 deletions modules/aruco/samples/create_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,14 +84,14 @@ int main(int argc, char *argv[]) {
return 0;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
6 changes: 3 additions & 3 deletions modules/aruco/samples/detect_board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ int main(int argc, char *argv[]) {
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
FileStorage fs(parser.get<string>("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;
Expand All @@ -118,14 +118,14 @@ int main(int argc, char *argv[]) {
return 0;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
6 changes: 3 additions & 3 deletions modules/aruco/samples/detect_board_charuco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ int main(int argc, char *argv[]) {
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
FileStorage fs(parser.get<string>("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;
Expand All @@ -114,14 +114,14 @@ int main(int argc, char *argv[]) {
return 0;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
6 changes: 3 additions & 3 deletions modules/aruco/samples/detect_diamonds.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ int main(int argc, char *argv[]) {
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
FileStorage fs(parser.get<string>("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;
Expand All @@ -114,14 +114,14 @@ int main(int argc, char *argv[]) {
return 0;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
6 changes: 3 additions & 3 deletions modules/aruco/samples/detect_markers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ int main(int argc, char *argv[]) {
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
FileStorage fs(parser.get<string>("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;
Expand All @@ -108,14 +108,14 @@ int main(int argc, char *argv[]) {
return 0;
}

Ptr<aruco::Dictionary> dictionary;
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(0);
if (parser.has("d")) {
int dictionaryId = parser.get<int>("d");
dictionary = aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
}
else if (parser.has("cd")) {
FileStorage fs(parser.get<std::string>("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;
Expand Down
44 changes: 21 additions & 23 deletions modules/aruco/src/aruco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<DetectorParameters>& 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;
}

Expand Down Expand Up @@ -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
Expand Down
Loading

0 comments on commit a10b397

Please sign in to comment.