Skip to content

Commit

Permalink
implemented cv::Algorithm - read/write, added read/write to RefinePar…
Browse files Browse the repository at this point in the history
…ameters, added write to DetectorParameters
  • Loading branch information
AleksandrPanov committed May 18, 2022
1 parent 9f4914a commit dfd8e9b
Show file tree
Hide file tree
Showing 4 changed files with 133 additions and 85 deletions.
2 changes: 0 additions & 2 deletions modules/aruco/include/opencv2/aruco/dictionary.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,6 @@ class CV_EXPORTS_W Dictionary {
CV_PROP_RW int maxCorrectionBits; // maximum number of bits that can be corrected


/**
*/
Dictionary(const Mat &_bytesList = Mat(), int _markerSize = 0, int _maxcorr = 0);


Expand Down
57 changes: 50 additions & 7 deletions modules/aruco/include/opencv2/aruco_detector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,10 +93,15 @@ struct CV_EXPORTS_W DetectorParameters {
}

/**
* @brief Read a new set of DetectorParameters from FileStorage.
* @brief Read a new set of DetectorParameters from FileNode (use FileStorage.root()).
*/
CV_WRAP bool readDetectorParameters(const FileNode& fn);

/**
* @brief Write a set of DetectorParameters to FileStorage
*/
CV_WRAP bool writeDetectorParameters(const Ptr<FileStorage>& fs);

/// minimum window size for adaptive thresholding before finding contours (default 3).
CV_PROP_RW int adaptiveThreshWinSizeMin;

Expand Down Expand Up @@ -214,6 +219,9 @@ struct CV_EXPORTS_W DetectorParameters {

/// range [0,1], eq (2) from paper. The parameter tau_i has a direct influence on the processing speed.
CV_PROP_RW float minMarkerLengthRatioOriginalImg;

private:
bool readWrite(const Ptr<FileNode>& readNode = nullptr, const Ptr<FileStorage>& writeStorage = nullptr);
};

struct CV_EXPORTS_W RefineParameters {
Expand All @@ -226,14 +234,22 @@ struct CV_EXPORTS_W RefineParameters {
RefineParameters(float _minRepDistance, float _errorCorrectionRate, bool _checkAllOrders):
minRepDistance(_minRepDistance), errorCorrectionRate(_errorCorrectionRate), checkAllOrders(_checkAllOrders) {}

CV_WRAP static Ptr<RefineParameters> create() {
return makePtr<RefineParameters>();
}

CV_WRAP static Ptr<RefineParameters> create(float _minRepDistance, float _errorCorrectionRate, bool _checkAllOrders) {
CV_WRAP static Ptr<RefineParameters> create(float _minRepDistance = 10.f, float _errorCorrectionRate = 3.f,
bool _checkAllOrders = true) {
return makePtr<RefineParameters>(_minRepDistance, _errorCorrectionRate, _checkAllOrders);
}


/**
* @brief Read a new set of RefineParameters from FileNode (use FileStorage.root()).
*/
CV_WRAP bool readRefineParameters(const FileNode& fn);

/**
* @brief Write a set of RefineParameters to FileStorage
*/
CV_WRAP bool writeRefineParameters(const Ptr<FileStorage>& fs);

/// minRepDistance minimum distance between the corners of the rejected candidate and the reprojected marker in
/// order to consider it as a correspondence.
CV_PROP_RW float minRepDistance;
Expand All @@ -243,9 +259,11 @@ struct CV_EXPORTS_W RefineParameters {
/// checkAllOrders consider the four posible corner orders in the rejectedCorners array.
// * If it set to false, only the provided corner order is considered (default true).
CV_PROP_RW bool checkAllOrders;
private:
bool readWrite(const Ptr<FileNode>& readNode = nullptr, const Ptr<FileStorage>& writeStorage = nullptr);
};

class CV_EXPORTS_W ArucoDetector
class CV_EXPORTS_W ArucoDetector : public Algorithm
{
public:
/// dictionary indicates the type of markers that will be searched
Expand Down Expand Up @@ -319,6 +337,31 @@ class CV_EXPORTS_W ArucoDetector
InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners,
InputArray cameraMatrix = noArray(), InputArray distCoeffs = noArray(),
OutputArray recoveredIdxs = noArray());

/** @brief Stores algorithm parameters in a file storage
*/
virtual void write(FileStorage& fs) const override {
Ptr<FileStorage> pfs = makePtr<FileStorage>(fs);
dictionary->writeDictionary(pfs);
params->writeDetectorParameters(pfs);
refineParams->writeRefineParameters(pfs);
}

/** @brief simplified API for language bindings
* @overload
*/
CV_WRAP void write(const String& fileName) const {
FileStorage fs(fileName, FileStorage::WRITE);
write(fs);
}

/** @brief Reads algorithm parameters from a file storage
*/
CV_WRAP virtual void read(const FileNode& fn) override {
dictionary->readDictionary(fn);
params->readDetectorParameters(fn);
refineParams->readRefineParameters(fn);
}
};

/**
Expand Down
115 changes: 71 additions & 44 deletions modules/aruco/src/aruco_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,48 +15,80 @@ namespace aruco {

using namespace std;

template<typename T>
static inline bool readParameter(const FileNode& node, T& parameter)
{
if (!node.empty()) {
node >> parameter;
return true;
}
return false;
bool DetectorParameters::readWrite(const Ptr<FileNode>& readNode, const Ptr<FileStorage>& writeStorage) {
CV_Assert(!readNode.empty() || !writeStorage.empty());
bool check = false;

check |= readWriteParameter("adaptiveThreshWinSizeMin", this->adaptiveThreshWinSizeMin, readNode, writeStorage);
check |= readWriteParameter("adaptiveThreshWinSizeMax", this->adaptiveThreshWinSizeMax, readNode, writeStorage);
check |= readWriteParameter("adaptiveThreshWinSizeStep", this->adaptiveThreshWinSizeStep, readNode, writeStorage);
check |= readWriteParameter("adaptiveThreshConstant", this->adaptiveThreshConstant, readNode, writeStorage);
check |= readWriteParameter("minMarkerPerimeterRate", this->minMarkerPerimeterRate, readNode, writeStorage);
check |= readWriteParameter("maxMarkerPerimeterRate", this->maxMarkerPerimeterRate, readNode, writeStorage);
check |= readWriteParameter("polygonalApproxAccuracyRate", this->polygonalApproxAccuracyRate,
readNode, writeStorage);
check |= readWriteParameter("minCornerDistanceRate", this->minCornerDistanceRate, readNode, writeStorage);
check |= readWriteParameter("minDistanceToBorder", this->minDistanceToBorder, readNode, writeStorage);
check |= readWriteParameter("minMarkerDistanceRate", this->minMarkerDistanceRate, readNode, writeStorage);
check |= readWriteParameter("cornerRefinementMethod", this->cornerRefinementMethod, readNode, writeStorage);
check |= readWriteParameter("cornerRefinementWinSize", this->cornerRefinementWinSize, readNode, writeStorage);
check |= readWriteParameter("cornerRefinementMaxIterations", this->cornerRefinementMaxIterations,
readNode, writeStorage);
check |= readWriteParameter("cornerRefinementMinAccuracy", this->cornerRefinementMinAccuracy,
readNode, writeStorage);
check |= readWriteParameter("markerBorderBits", this->markerBorderBits, readNode, writeStorage);
check |= readWriteParameter("perspectiveRemovePixelPerCell", this->perspectiveRemovePixelPerCell,
readNode, writeStorage);
check |= readWriteParameter("perspectiveRemoveIgnoredMarginPerCell", this->perspectiveRemoveIgnoredMarginPerCell,
readNode, writeStorage);
check |= readWriteParameter("maxErroneousBitsInBorderRate", this->maxErroneousBitsInBorderRate,
readNode, writeStorage);
check |= readWriteParameter("minOtsuStdDev", this->minOtsuStdDev, readNode, writeStorage);
check |= readWriteParameter("errorCorrectionRate", this->errorCorrectionRate, readNode, writeStorage);
// new aruco 3 functionality
check |= readWriteParameter("useAruco3Detection", this->useAruco3Detection, readNode, writeStorage);
check |= readWriteParameter("minSideLengthCanonicalImg", this->minSideLengthCanonicalImg, readNode, writeStorage);
check |= readWriteParameter("minMarkerLengthRatioOriginalImg", this->minMarkerLengthRatioOriginalImg,
readNode, writeStorage);
return check;
}

bool DetectorParameters::readDetectorParameters(const FileNode& fn) {
if(fn.empty())
return false;
Ptr<FileNode> pfn = makePtr<FileNode>(fn);
return readWrite(pfn);
}

bool DetectorParameters::readDetectorParameters(const FileNode& fn)
bool DetectorParameters::writeDetectorParameters(const Ptr<FileStorage>& fs)
{
if (fs.empty() && !fs->isOpened())
return false;
return readWrite(nullptr, fs);
}

bool RefineParameters::readWrite(const Ptr<FileNode>& readNode, const Ptr<FileStorage>& writeStorage) {
CV_Assert(!readNode.empty() || !writeStorage.empty());
bool check = false;

check |= readWriteParameter("minRepDistance", this->minRepDistance, readNode, writeStorage);
check |= readWriteParameter("errorCorrectionRate", this->errorCorrectionRate, readNode, writeStorage);
check |= readWriteParameter("checkAllOrders", this->checkAllOrders, readNode, writeStorage);
return check;
}

bool RefineParameters::readRefineParameters(const FileNode &fn) {
if(fn.empty())
return true;
bool checkRead = false;
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);
// new aruco 3 functionality
checkRead |= readParameter(fn["useAruco3Detection"], this->useAruco3Detection);
checkRead |= readParameter(fn["minSideLengthCanonicalImg"], this->minSideLengthCanonicalImg);
checkRead |= readParameter(fn["minMarkerLengthRatioOriginalImg"], this->minMarkerLengthRatioOriginalImg);
return checkRead;
return false;
Ptr<FileNode> pfn = makePtr<FileNode>(fn);
return readWrite(pfn);
}

bool RefineParameters::writeRefineParameters(const Ptr<FileStorage> &fs) {
if(fs.empty())
return false;
return readWrite(nullptr, fs);
}

/**
* @brief Threshold input image using adaptive thresholding
Expand Down Expand Up @@ -163,7 +195,7 @@ static void _reorderCandidatesCorners(vector< vector< Point2f > > &candidates) {
/**
* @brief to make sure that the corner's order of both candidates (default/white) is the same
*/
static vector< Point2f > alignContourOrder( Point2f corner, vector< Point2f > candidate){
static vector<Point2f> alignContourOrder(Point2f corner, vector< Point2f > candidate) {
uint8_t r=0;
double min = cv::norm( Vec2f( corner - candidate[0] ), NORM_L2SQR);
for(uint8_t pos=1; pos < 4; pos++) {
Expand Down Expand Up @@ -478,8 +510,7 @@ static int _getBorderErrors(const Mat &bits, int markerSize, int borderSize) {
static uint8_t _identifyOneCandidate(const Ptr<Dictionary>& dictionary, InputArray _image,
const vector<Point2f>& _corners, int& idx,
const Ptr<DetectorParameters>& params, int& rotation,
const float scale = 1.f)
{
const float scale = 1.f) {
CV_DbgAssert(_corners.size() == 4);
CV_DbgAssert(_image.getMat().total() != 0);
CV_DbgAssert(params->markerBorderBits > 0);
Expand Down Expand Up @@ -1017,7 +1048,6 @@ void ArucoDetector::refineDetectedMarkers(InputArray _image, const Ptr<Board> &_
InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds,
InputOutputArrayOfArrays _rejectedCorners, InputArray _cameraMatrix,
InputArray _distCoeffs, OutputArray _recoveredIdxs) {

CV_Assert(refineParams->minRepDistance > 0);

if(_detectedIds.total() == 0 || _rejectedCorners.total() == 0) return;
Expand Down Expand Up @@ -1177,12 +1207,9 @@ void ArucoDetector::refineDetectedMarkers(InputArray _image, const Ptr<Board> &_
}
}

/**
*/

void drawDetectedMarkers(InputOutputArray _image, InputArrayOfArrays _corners,
InputArray _ids, Scalar borderColor) {


CV_Assert(_image.getMat().total() != 0 &&
(_image.getMat().channels() == 1 || _image.getMat().channels() == 3));
CV_Assert((_corners.total() == _ids.total()) || _ids.total() == 0);
Expand Down
44 changes: 12 additions & 32 deletions modules/aruco/src/dictionary.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,14 @@ or tort (including negligence or otherwise) arising in any way out of
the use of this software, even if advised of the possibility of such damage.
*/

#include "precomp.hpp"
#include "opencv2/aruco/dictionary.hpp"
#include <opencv2/core.hpp>
#include <opencv2/imgproc.hpp>
#include "opencv2/core/hal/hal.hpp"

#include "precomp.hpp"
#include "aruco_utils.hpp"
#include "predefined_dictionaries.hpp"
#include "apriltag/predefined_dictionaries_apriltag.hpp"
#include "opencv2/core/hal/hal.hpp"
#include <opencv2/aruco/dictionary.hpp>

namespace cv {
namespace aruco {
Expand Down Expand Up @@ -72,40 +73,27 @@ Ptr<Dictionary> Dictionary::create(int nMarkers, int markerSize, int randomSeed)

Ptr<Dictionary> Dictionary::create(int nMarkers, int markerSize,
const Ptr<Dictionary> &baseDictionary, int randomSeed) {

return generateCustomDictionary(nMarkers, markerSize, baseDictionary, randomSeed);
}


template<typename T>
static inline bool readParameter(const FileNode& node, T& parameter)
{
if (!node.empty()) {
node >> parameter;
return true;
}
return false;
}


bool Dictionary::readDictionary(const cv::FileNode& fn)
{
bool Dictionary::readDictionary(const cv::FileNode& fn) {
int nMarkers = 0, _markerSize = 0;
if (fn.empty() || !readParameter(fn["nmarkers"], nMarkers) || !readParameter(fn["markersize"], _markerSize))
if (fn.empty() || !readParameter("nmarkers", nMarkers, fn) || !readParameter("markersize", _markerSize, fn))
return false;
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))
if (!readParameter("marker_" + ostr.str(), markerString, fn))
return false;
for (int j = 0; j < (int) markerString.size(); j++)
marker.at<unsigned char>(j) = (markerString[j] == '0') ? 0 : 1;
bytes.push_back(Dictionary::getByteListFromBits(marker));
}
int _maxCorrectionBits = 0;
readParameter(fn["maxCorrectionBits"], _maxCorrectionBits);
readParameter("maxCorrectionBits", _maxCorrectionBits, fn);
*this = Dictionary(bytes, _markerSize, _maxCorrectionBits);
return true;
}
Expand Down Expand Up @@ -134,9 +122,7 @@ Ptr<Dictionary> Dictionary::get(int dict) {
}


bool Dictionary::identify(const Mat &onlyBits, int &idx, int &rotation,
double maxCorrectionRate) const {

bool Dictionary::identify(const Mat &onlyBits, int &idx, int &rotation, double maxCorrectionRate) const {
CV_Assert(onlyBits.rows == markerSize && onlyBits.cols == markerSize);

int maxCorrectionRecalculed = int(double(maxCorrectionBits) * maxCorrectionRate);
Expand Down Expand Up @@ -198,7 +184,6 @@ int Dictionary::getDistanceToId(InputArray bits, int id, bool allRotations) cons


void Dictionary::drawMarker(int id, int sidePixels, OutputArray _img, int borderBits) const {

CV_Assert(sidePixels >= (markerSize + 2*borderBits));
CV_Assert(id < bytesList.rows);
CV_Assert(borderBits > 0);
Expand All @@ -220,7 +205,6 @@ void Dictionary::drawMarker(int id, int sidePixels, OutputArray _img, int border
}



Mat Dictionary::getByteListFromBits(const Mat &bits) {
// integer ceil
int nbytes = (bits.cols * bits.rows + 8 - 1) / 8;
Expand Down Expand Up @@ -293,8 +277,7 @@ Mat Dictionary::getBitsFromByteList(const Mat &byteList, int markerSize) {
}


Ptr<Dictionary> getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name)
{
Ptr<Dictionary> getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name) {
// DictionaryData constructors calls
// moved out of globals so construted on first use, which allows lazy-loading of opencv dll
static const Dictionary DICT_ARUCO_DATA = Dictionary(Mat(1024, (5 * 5 + 7) / 8, CV_8UC4, (uchar*)DICT_ARUCO_BYTES), 5, 0);
Expand Down Expand Up @@ -415,8 +398,7 @@ static int _getSelfDistance(const Mat &marker) {
return minHamming;
}

/**
*/

Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize,
const Ptr<Dictionary> &baseDictionary, int randomSeed) {
RNG rng((uint64)(randomSeed));
Expand Down Expand Up @@ -507,8 +489,6 @@ Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize,
}


/**
*/
Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize, int randomSeed) {
Ptr<Dictionary> baseDictionary = makePtr<Dictionary>();
return generateCustomDictionary(nMarkers, markerSize, baseDictionary, randomSeed);
Expand Down

0 comments on commit dfd8e9b

Please sign in to comment.