Skip to content

Commit

Permalink
fix ArUco, ChArUco, diamonds, add read dictionary/params, add calibra…
Browse files Browse the repository at this point in the history
…tion photos, add tests, add aruco_samples_utility.hpp
  • Loading branch information
AleksandrPanov committed Dec 18, 2021
1 parent 5cc328d commit a965b9b
Show file tree
Hide file tree
Showing 42 changed files with 749 additions and 430 deletions.
29 changes: 29 additions & 0 deletions modules/aruco/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,2 +1,31 @@
set(the_description "ArUco Marker Detection")
ocv_define_module(aruco opencv_core opencv_imgproc opencv_calib3d WRAP python java)
ocv_include_directories(${CMAKE_CURRENT_BINARY_DIR})

ocv_add_testdata(samples/ contrib/aruco
FILES_MATCHING PATTERN "*yml"
)

ocv_add_testdata(tutorials/aruco_detection/images/ contrib/aruco
FILES_MATCHING PATTERN "singlemarkersoriginal.jpg"
)

ocv_add_testdata(tutorials/aruco_board_detection/images/ contrib/aruco
FILES_MATCHING PATTERN "gboriginal.png"
)

ocv_add_testdata(tutorials/charuco_detection/images/ contrib/aruco
FILES_MATCHING PATTERN "choriginal.jpg"
)

ocv_add_testdata(tutorials/charuco_detection/images/ contrib/aruco
FILES_MATCHING PATTERN "chocclusion_original.jpg"
)

ocv_add_testdata(tutorials/charuco_diamond_detection/images/ contrib/aruco
FILES_MATCHING PATTERN "diamondmarkers.png"
)

ocv_add_testdata(tutorials/aruco_calibration/images/ contrib/aruco
FILES_MATCHING REGEX "img_[0-9]+.jpg"
)
2 changes: 1 addition & 1 deletion modules/aruco/include/opencv2/aruco.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,8 +150,8 @@ enum CornerRefineMethod{
struct CV_EXPORTS_W DetectorParameters {

DetectorParameters();

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

CV_PROP_RW int adaptiveThreshWinSizeMin;
CV_PROP_RW int adaptiveThreshWinSizeMax;
Expand Down
10 changes: 10 additions & 0 deletions modules/aruco/include/opencv2/aruco/dictionary.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,16 @@ class CV_EXPORTS_W Dictionary {
CV_WRAP_AS(create_from) static Ptr<Dictionary> create(int nMarkers, int markerSize,
const Ptr<Dictionary> &baseDictionary, int randomSeed=0);

/**
* @brief Read a new dictionary from FileNode. Format:
* nmarkers: 35
* markersize: 6
* marker_0: "101011111011111001001001101100000000"
* ...
* marker_34: "011111010000111011111110110101100101"
*/
CV_WRAP static bool readDictionary(const cv::FileNode& fn, cv::Ptr<cv::aruco::Dictionary> &dictionary);

/**
* @see getPredefinedDictionary
*/
Expand Down
48 changes: 48 additions & 0 deletions modules/aruco/samples/aruco_samples_utility.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
#include <opencv2/highgui.hpp>
#include <opencv2/aruco.hpp>
#include <opencv2/calib3d.hpp>
#include <ctime>

namespace {
inline static bool readCameraParameters(std::string filename, cv::Mat &camMatrix, cv::Mat &distCoeffs) {
cv::FileStorage fs(filename, cv::FileStorage::READ);
if (!fs.isOpened())
return false;
fs["camera_matrix"] >> camMatrix;
fs["distortion_coefficients"] >> distCoeffs;
return true;
}

inline static bool saveCameraParams(const std::string &filename, cv::Size imageSize, float aspectRatio, int flags,
const cv::Mat &cameraMatrix, const cv::Mat &distCoeffs, double totalAvgErr) {
cv::FileStorage fs(filename, cv::FileStorage::WRITE);
if (!fs.isOpened())
return false;

time_t tt;
time(&tt);
struct tm *t2 = localtime(&tt);
char buf[1024];
strftime(buf, sizeof(buf) - 1, "%c", t2);

fs << "calibration_time" << buf;
fs << "image_width" << imageSize.width;
fs << "image_height" << imageSize.height;

if (flags & cv::CALIB_FIX_ASPECT_RATIO) fs << "aspectRatio" << aspectRatio;

if (flags != 0) {
sprintf(buf, "flags: %s%s%s%s",
flags & cv::CALIB_USE_INTRINSIC_GUESS ? "+use_intrinsic_guess" : "",
flags & cv::CALIB_FIX_ASPECT_RATIO ? "+fix_aspectRatio" : "",
flags & cv::CALIB_FIX_PRINCIPAL_POINT ? "+fix_principal_point" : "",
flags & cv::CALIB_ZERO_TANGENT_DIST ? "+zero_tangent_dist" : "");
}
fs << "flags" << flags;
fs << "camera_matrix" << cameraMatrix;
fs << "distortion_coefficients" << distCoeffs;
fs << "avg_reprojection_error" << totalAvgErr;
return true;
}

}
100 changes: 22 additions & 78 deletions modules/aruco/samples/calibrate_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ the use of this software, even if advised of the possibility of such damage.
#include <vector>
#include <iostream>
#include <ctime>
#include "aruco_samples_utility.hpp"

using namespace std;
using namespace cv;
Expand All @@ -64,6 +65,7 @@ const char* keys =
"DICT_4X4_1000=3, DICT_5X5_50=4, DICT_5X5_100=5, DICT_5X5_250=6, DICT_5X5_1000=7, "
"DICT_6X6_50=8, DICT_6X6_100=9, DICT_6X6_250=10, DICT_6X6_1000=11, DICT_7X7_50=12,"
"DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16}"
"{cd | | Input file with custom dictionary }"
"{@outfile |<none> | Output file with calibrated camera parameters }"
"{v | | Input from video file, if ommited, input comes from camera }"
"{ci | 0 | Camera id if input doesnt come from video (-v) }"
Expand All @@ -74,80 +76,7 @@ const char* keys =
"{pc | false | Fix the principal point at the center }";
}

/**
*/
static bool readDetectorParameters(string filename, Ptr<aruco::DetectorParameters> &params) {
FileStorage fs(filename, FileStorage::READ);
if(!fs.isOpened())
return false;
fs["adaptiveThreshWinSizeMin"] >> params->adaptiveThreshWinSizeMin;
fs["adaptiveThreshWinSizeMax"] >> params->adaptiveThreshWinSizeMax;
fs["adaptiveThreshWinSizeStep"] >> params->adaptiveThreshWinSizeStep;
fs["adaptiveThreshConstant"] >> params->adaptiveThreshConstant;
fs["minMarkerPerimeterRate"] >> params->minMarkerPerimeterRate;
fs["maxMarkerPerimeterRate"] >> params->maxMarkerPerimeterRate;
fs["polygonalApproxAccuracyRate"] >> params->polygonalApproxAccuracyRate;
fs["minCornerDistanceRate"] >> params->minCornerDistanceRate;
fs["minDistanceToBorder"] >> params->minDistanceToBorder;
fs["minMarkerDistanceRate"] >> params->minMarkerDistanceRate;
fs["cornerRefinementMethod"] >> params->cornerRefinementMethod;
fs["cornerRefinementWinSize"] >> params->cornerRefinementWinSize;
fs["cornerRefinementMaxIterations"] >> params->cornerRefinementMaxIterations;
fs["cornerRefinementMinAccuracy"] >> params->cornerRefinementMinAccuracy;
fs["markerBorderBits"] >> params->markerBorderBits;
fs["perspectiveRemovePixelPerCell"] >> params->perspectiveRemovePixelPerCell;
fs["perspectiveRemoveIgnoredMarginPerCell"] >> params->perspectiveRemoveIgnoredMarginPerCell;
fs["maxErroneousBitsInBorderRate"] >> params->maxErroneousBitsInBorderRate;
fs["minOtsuStdDev"] >> params->minOtsuStdDev;
fs["errorCorrectionRate"] >> params->errorCorrectionRate;
return true;
}



/**
*/
static bool saveCameraParams(const string &filename, Size imageSize, float aspectRatio, int flags,
const Mat &cameraMatrix, const Mat &distCoeffs, double totalAvgErr) {
FileStorage fs(filename, FileStorage::WRITE);
if(!fs.isOpened())
return false;

time_t tt;
time(&tt);
struct tm *t2 = localtime(&tt);
char buf[1024];
strftime(buf, sizeof(buf) - 1, "%c", t2);

fs << "calibration_time" << buf;

fs << "image_width" << imageSize.width;
fs << "image_height" << imageSize.height;

if(flags & CALIB_FIX_ASPECT_RATIO) fs << "aspectRatio" << aspectRatio;

if(flags != 0) {
sprintf(buf, "flags: %s%s%s%s",
flags & CALIB_USE_INTRINSIC_GUESS ? "+use_intrinsic_guess" : "",
flags & CALIB_FIX_ASPECT_RATIO ? "+fix_aspectRatio" : "",
flags & CALIB_FIX_PRINCIPAL_POINT ? "+fix_principal_point" : "",
flags & CALIB_ZERO_TANGENT_DIST ? "+zero_tangent_dist" : "");
}

fs << "flags" << flags;

fs << "camera_matrix" << cameraMatrix;
fs << "distortion_coefficients" << distCoeffs;

fs << "avg_reprojection_error" << totalAvgErr;

return true;
}



/**
*/
int main(int argc, char *argv[]) {
CommandLineParser parser(argc, argv, keys);
parser.about(about);
Expand All @@ -161,7 +90,6 @@ int main(int argc, char *argv[]) {
int markersY = parser.get<int>("h");
float markerLength = parser.get<float>("l");
float markerSeparation = parser.get<float>("s");
int dictionaryId = parser.get<int>("d");
string outputFile = parser.get<String>(0);

int calibrationFlags = 0;
Expand All @@ -173,9 +101,10 @@ int main(int argc, char *argv[]) {
if(parser.get<bool>("zt")) calibrationFlags |= CALIB_ZERO_TANGENT_DIST;
if(parser.get<bool>("pc")) calibrationFlags |= CALIB_FIX_PRINCIPAL_POINT;

Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
Ptr<aruco::DetectorParameters> detectorParams;
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);
if(!readOk) {
cerr << "Invalid detector parameters file" << endl;
return 0;
Expand Down Expand Up @@ -205,8 +134,23 @@ int main(int argc, char *argv[]) {
waitTime = 10;
}

Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
Ptr<aruco::Dictionary> dictionary;
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);
if(!readOk) {
cerr << "Invalid dictionary file" << endl;
return 0;
}
}
else {
cerr << "Dictionary not specified" << endl;
return 0;
}

// create board object
Ptr<aruco::GridBoard> gridboard =
Expand Down
101 changes: 22 additions & 79 deletions modules/aruco/samples/calibrate_camera_charuco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ the use of this software, even if advised of the possibility of such damage.
#include <opencv2/imgproc.hpp>
#include <vector>
#include <iostream>
#include <ctime>
#include "aruco_samples_utility.hpp"

using namespace std;
using namespace cv;
Expand All @@ -63,6 +63,7 @@ const char* keys =
"DICT_4X4_1000=3, DICT_5X5_50=4, DICT_5X5_100=5, DICT_5X5_250=6, DICT_5X5_1000=7, "
"DICT_6X6_50=8, DICT_6X6_100=9, DICT_6X6_250=10, DICT_6X6_1000=11, DICT_7X7_50=12,"
"DICT_7X7_100=13, DICT_7X7_250=14, DICT_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16}"
"{cd | | Input file with custom dictionary }"
"{@outfile |<none> | Output file with calibrated camera parameters }"
"{v | | Input from video file, if ommited, input comes from camera }"
"{ci | 0 | Camera id if input doesnt come from video (-v) }"
Expand All @@ -74,80 +75,7 @@ const char* keys =
"{sc | false | Show detected chessboard corners after calibration }";
}

/**
*/
static bool readDetectorParameters(string filename, Ptr<aruco::DetectorParameters> &params) {
FileStorage fs(filename, FileStorage::READ);
if(!fs.isOpened())
return false;
fs["adaptiveThreshWinSizeMin"] >> params->adaptiveThreshWinSizeMin;
fs["adaptiveThreshWinSizeMax"] >> params->adaptiveThreshWinSizeMax;
fs["adaptiveThreshWinSizeStep"] >> params->adaptiveThreshWinSizeStep;
fs["adaptiveThreshConstant"] >> params->adaptiveThreshConstant;
fs["minMarkerPerimeterRate"] >> params->minMarkerPerimeterRate;
fs["maxMarkerPerimeterRate"] >> params->maxMarkerPerimeterRate;
fs["polygonalApproxAccuracyRate"] >> params->polygonalApproxAccuracyRate;
fs["minCornerDistanceRate"] >> params->minCornerDistanceRate;
fs["minDistanceToBorder"] >> params->minDistanceToBorder;
fs["minMarkerDistanceRate"] >> params->minMarkerDistanceRate;
fs["cornerRefinementMethod"] >> params->cornerRefinementMethod;
fs["cornerRefinementWinSize"] >> params->cornerRefinementWinSize;
fs["cornerRefinementMaxIterations"] >> params->cornerRefinementMaxIterations;
fs["cornerRefinementMinAccuracy"] >> params->cornerRefinementMinAccuracy;
fs["markerBorderBits"] >> params->markerBorderBits;
fs["perspectiveRemovePixelPerCell"] >> params->perspectiveRemovePixelPerCell;
fs["perspectiveRemoveIgnoredMarginPerCell"] >> params->perspectiveRemoveIgnoredMarginPerCell;
fs["maxErroneousBitsInBorderRate"] >> params->maxErroneousBitsInBorderRate;
fs["minOtsuStdDev"] >> params->minOtsuStdDev;
fs["errorCorrectionRate"] >> params->errorCorrectionRate;
return true;
}



/**
*/
static bool saveCameraParams(const string &filename, Size imageSize, float aspectRatio, int flags,
const Mat &cameraMatrix, const Mat &distCoeffs, double totalAvgErr) {
FileStorage fs(filename, FileStorage::WRITE);
if(!fs.isOpened())
return false;

time_t tt;
time(&tt);
struct tm *t2 = localtime(&tt);
char buf[1024];
strftime(buf, sizeof(buf) - 1, "%c", t2);

fs << "calibration_time" << buf;

fs << "image_width" << imageSize.width;
fs << "image_height" << imageSize.height;

if(flags & CALIB_FIX_ASPECT_RATIO) fs << "aspectRatio" << aspectRatio;

if(flags != 0) {
sprintf(buf, "flags: %s%s%s%s",
flags & CALIB_USE_INTRINSIC_GUESS ? "+use_intrinsic_guess" : "",
flags & CALIB_FIX_ASPECT_RATIO ? "+fix_aspectRatio" : "",
flags & CALIB_FIX_PRINCIPAL_POINT ? "+fix_principal_point" : "",
flags & CALIB_ZERO_TANGENT_DIST ? "+zero_tangent_dist" : "");
}

fs << "flags" << flags;

fs << "camera_matrix" << cameraMatrix;
fs << "distortion_coefficients" << distCoeffs;

fs << "avg_reprojection_error" << totalAvgErr;

return true;
}



/**
*/
int main(int argc, char *argv[]) {
CommandLineParser parser(argc, argv, keys);
parser.about(about);
Expand All @@ -161,7 +89,6 @@ int main(int argc, char *argv[]) {
int squaresY = parser.get<int>("h");
float squareLength = parser.get<float>("sl");
float markerLength = parser.get<float>("ml");
int dictionaryId = parser.get<int>("d");
string outputFile = parser.get<string>(0);

bool showChessboardCorners = parser.get<bool>("sc");
Expand All @@ -175,9 +102,10 @@ int main(int argc, char *argv[]) {
if(parser.get<bool>("zt")) calibrationFlags |= CALIB_ZERO_TANGENT_DIST;
if(parser.get<bool>("pc")) calibrationFlags |= CALIB_FIX_PRINCIPAL_POINT;

Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
Ptr<aruco::DetectorParameters> detectorParams;
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);
if(!readOk) {
cerr << "Invalid detector parameters file" << endl;
return 0;
Expand Down Expand Up @@ -207,8 +135,23 @@ int main(int argc, char *argv[]) {
waitTime = 10;
}

Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
Ptr<aruco::Dictionary> dictionary;
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);
if(!readOk) {
cerr << "Invalid dictionary file" << endl;
return 0;
}
}
else {
cerr << "Dictionary not specified" << endl;
return 0;
}

// create charuco board object
Ptr<aruco::CharucoBoard> charucoboard =
Expand Down
Loading

0 comments on commit a965b9b

Please sign in to comment.