Commit 063c191d authored by folz's avatar folz

aruco: Use shared Ptrs to support exporting

parent 9b06bb28
This diff is collapsed.
......@@ -59,7 +59,7 @@ namespace aruco {
* calibration and pose estimation.
* This class also allows the easy creation and drawing of ChArUco boards.
*/
class CV_EXPORTS CharucoBoard : public Board {
class CV_EXPORTS_W CharucoBoard : public Board {
public:
// vector of chessboard 3D corners precalculated
......@@ -97,8 +97,8 @@ class CV_EXPORTS CharucoBoard : public Board {
* This functions creates a CharucoBoard object given the number of squares in each direction
* and the size of the markers and chessboard squares.
*/
static CharucoBoard create(int squaresX, int squaresY, float squareLength, float markerLength,
Dictionary dictionary);
CV_WRAP static Ptr<CharucoBoard> create(int squaresX, int squaresY, float squareLength,
float markerLength, Ptr<Dictionary> &dictionary);
/**
*
......@@ -154,11 +154,11 @@ class CV_EXPORTS CharucoBoard : public Board {
* also returned in charucoIds.
* The function returns the number of interpolated corners.
*/
CV_EXPORTS int interpolateCornersCharuco(InputArrayOfArrays markerCorners, InputArray markerIds,
InputArray image, const CharucoBoard &board,
OutputArray charucoCorners, OutputArray charucoIds,
InputArray cameraMatrix = noArray(),
InputArray distCoeffs = noArray());
CV_EXPORTS_W int interpolateCornersCharuco(InputArrayOfArrays markerCorners, InputArray markerIds,
InputArray image, Ptr<CharucoBoard> &board,
OutputArray charucoCorners, OutputArray charucoIds,
InputArray cameraMatrix = noArray(),
InputArray distCoeffs = noArray());
......@@ -180,9 +180,9 @@ CV_EXPORTS int interpolateCornersCharuco(InputArrayOfArrays markerCorners, Input
* The function checks if the input corners are enough and valid to perform pose estimation.
* If pose estimation is valid, returns true, else returns false.
*/
CV_EXPORTS bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray charucoIds,
CharucoBoard &board, InputArray cameraMatrix,
InputArray distCoeffs, OutputArray rvec, OutputArray tvec);
CV_EXPORTS_W bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray charucoIds,
Ptr<CharucoBoard> &board, InputArray cameraMatrix,
InputArray distCoeffs, OutputArray rvec, OutputArray tvec);
......@@ -198,9 +198,9 @@ CV_EXPORTS bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray c
* This function draws a set of detected Charuco corners. If identifiers vector is provided, it also
* draws the id of each corner.
*/
CV_EXPORTS void drawDetectedCornersCharuco(InputOutputArray image, InputArray charucoCorners,
InputArray charucoIds = noArray(),
Scalar cornerColor = Scalar(255, 0, 0));
CV_EXPORTS_W void drawDetectedCornersCharuco(InputOutputArray image, InputArray charucoCorners,
InputArray charucoIds = noArray(),
Scalar cornerColor = Scalar(255, 0, 0));
......@@ -230,8 +230,8 @@ CV_EXPORTS void drawDetectedCornersCharuco(InputOutputArray image, InputArray ch
* receives a list of detected corners and its identifiers from several views of the Board.
* The function returns the final re-projection error.
*/
CV_EXPORTS double calibrateCameraCharuco(
InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds, const CharucoBoard &board,
CV_EXPORTS_W double calibrateCameraCharuco(
InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds, Ptr<CharucoBoard> &board,
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs = noArray(), OutputArrayOfArrays tvecs = noArray(), int flags = 0,
TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
......@@ -261,11 +261,11 @@ CV_EXPORTS double calibrateCameraCharuco(
* are provided, the diamond search is based on reprojection. If not, diamond search is based on
* homography. Homography is faster than reprojection but can slightly reduce the detection rate.
*/
CV_EXPORTS void detectCharucoDiamond(InputArray image, InputArrayOfArrays markerCorners,
InputArray markerIds, float squareMarkerLengthRate,
OutputArrayOfArrays diamondCorners, OutputArray diamondIds,
InputArray cameraMatrix = noArray(),
InputArray distCoeffs = noArray());
CV_EXPORTS_W void detectCharucoDiamond(InputArray image, InputArrayOfArrays markerCorners,
InputArray markerIds, float squareMarkerLengthRate,
OutputArrayOfArrays diamondCorners, OutputArray diamondIds,
InputArray cameraMatrix = noArray(),
InputArray distCoeffs = noArray());
......@@ -287,9 +287,9 @@ CV_EXPORTS void detectCharucoDiamond(InputArray image, InputArrayOfArrays marker
* are painted and the markers identifiers if provided.
* Useful for debugging purposes.
*/
CV_EXPORTS void drawDetectedDiamonds(InputOutputArray image, InputArrayOfArrays diamondCorners,
InputArray diamondIds = noArray(),
Scalar borderColor = Scalar(0, 0, 255));
CV_EXPORTS_W void drawDetectedDiamonds(InputOutputArray image, InputArrayOfArrays diamondCorners,
InputArray diamondIds = noArray(),
Scalar borderColor = Scalar(0, 0, 255));
......@@ -308,7 +308,8 @@ CV_EXPORTS void drawDetectedDiamonds(InputOutputArray image, InputArrayOfArrays
*
* This function return the image of a ChArUco marker, ready to be printed.
*/
CV_EXPORTS void drawCharucoDiamond(Dictionary dictionary, Vec4i ids, int squareLength,
// TODO cannot be exported yet; conversion from/to Vec4i is not wrapped in core
CV_EXPORTS void drawCharucoDiamond(Ptr<Dictionary> &dictionary, Vec4i ids, int squareLength,
int markerLength, OutputArray img, int marginSize = 0,
int borderBits = 1);
......
......@@ -58,12 +58,12 @@ namespace aruco {
*
* `bytesList.ptr(i)[k*nbytes + j]` is then the j-th byte of i-th marker, in its k-th rotation.
*/
class CV_EXPORTS Dictionary {
class CV_EXPORTS_W Dictionary {
public:
Mat bytesList; // marker code information
int markerSize; // number of bits per dimension
int maxCorrectionBits; // maximum number of bits that can be corrected
CV_PROP_RW Mat bytesList; // marker code information
CV_PROP_RW int markerSize; // number of bits per dimension
CV_PROP_RW int maxCorrectionBits; // maximum number of bits that can be corrected
/**
......@@ -71,6 +71,32 @@ class CV_EXPORTS Dictionary {
Dictionary(const Mat &_bytesList = Mat(), int _markerSize = 0, int _maxcorr = 0);
/**
Dictionary(const Dictionary &_dictionary);
*/
/**
*/
Dictionary(const Ptr<Dictionary> &_dictionary);
/**
* @see generateCustomDictionary
*/
CV_WRAP_AS(create) static Ptr<Dictionary> create(int nMarkers, int markerSize);
/**
* @see generateCustomDictionary
*/
CV_WRAP_AS(create_from) static Ptr<Dictionary> create(int nMarkers, int markerSize,
Ptr<Dictionary> &baseDictionary);
/**
* @see getPredefinedDictionary
*/
CV_WRAP static Ptr<Dictionary> get(int dict);
/**
* @brief Given a matrix of bits. Returns whether if marker is identified or not.
......@@ -109,9 +135,10 @@ class CV_EXPORTS Dictionary {
/**
* @brief Predefined markers dictionaries/sets
* Each dictionary indicates the number of bits and the number of markers contained
* - DICT_ARUCO: standard ArUco Library Markers. 1024 markers, 5x5 bits, 0 minimum distance
* - DICT_ARUCO_ORIGINAL: standard ArUco Library Markers. 1024 markers, 5x5 bits, 0 minimum
distance
*/
enum PREDEFINED_DICTIONARY_NAME {
enum CV_EXPORTS_W_SIMPLE PREDEFINED_DICTIONARY_NAME {
DICT_4X4_50 = 0,
DICT_4X4_100,
DICT_4X4_250,
......@@ -135,7 +162,21 @@ enum PREDEFINED_DICTIONARY_NAME {
/**
* @brief Returns one of the predefined dictionaries defined in PREDEFINED_DICTIONARY_NAME
*/
CV_EXPORTS const Dictionary &getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name);
CV_EXPORTS Ptr<Dictionary> getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name);
/**
* @brief Returns one of the predefined dictionaries referenced by DICT_*.
*/
CV_EXPORTS_W Ptr<Dictionary> getPredefinedDictionary(int dict);
/**
* @see generateCustomDictionary
*/
CV_EXPORTS_AS(custom_dictionary) Ptr<Dictionary> generateCustomDictionary(
int nMarkers,
int markerSize);
/**
......@@ -150,8 +191,10 @@ CV_EXPORTS const Dictionary &getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME
* included and the rest are generated based on them. If the size of baseDictionary is higher
* than nMarkers, only the first nMarkers in baseDictionary are taken and no new marker is added.
*/
CV_EXPORTS Dictionary generateCustomDictionary(int nMarkers, int markerSize,
const Dictionary &baseDictionary = Dictionary());
CV_EXPORTS_AS(custom_dictionary_from) Ptr<Dictionary> generateCustomDictionary(
int nMarkers,
int markerSize,
Ptr<Dictionary> &baseDictionary);
......
......@@ -76,30 +76,30 @@ const char* keys =
/**
*/
static bool readDetectorParameters(string filename, aruco::DetectorParameters &params) {
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["doCornerRefinement"] >> params.doCornerRefinement;
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;
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["doCornerRefinement"] >> params->doCornerRefinement;
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;
}
......@@ -173,7 +173,7 @@ 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;
aruco::DetectorParameters detectorParams;
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
if(!readOk) {
......@@ -205,12 +205,13 @@ int main(int argc, char *argv[]) {
waitTime = 10;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
// create board object
aruco::GridBoard board =
aruco::GridBoard::create(markersX, markersY, markerLength, markerSeparation, dictionary);
Ptr<aruco::GridBoard> gridboard =
aruco::GridBoard::create(markersX, markersY, markerLength, markerSeparation, dictionary);
Ptr<aruco::Board> board = gridboard.staticCast<aruco::Board>();
// collected frames for calibration
vector< vector< vector< Point2f > > > allCorners;
......
......@@ -76,30 +76,30 @@ const char* keys =
/**
*/
static bool readDetectorParameters(string filename, aruco::DetectorParameters &params) {
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["doCornerRefinement"] >> params.doCornerRefinement;
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;
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["doCornerRefinement"] >> params->doCornerRefinement;
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;
}
......@@ -175,7 +175,7 @@ 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;
aruco::DetectorParameters detectorParams;
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
if(!readOk) {
......@@ -207,12 +207,13 @@ int main(int argc, char *argv[]) {
waitTime = 10;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
// create charuco board object
aruco::CharucoBoard board =
aruco::CharucoBoard::create(squaresX, squaresY, squareLength, markerLength, dictionary);
Ptr<aruco::CharucoBoard> charucoboard =
aruco::CharucoBoard::create(squaresX, squaresY, squareLength, markerLength, dictionary);
Ptr<aruco::Board> board = charucoboard.staticCast<aruco::Board>();
// collect data from each frame
vector< vector< vector< Point2f > > > allCorners;
......@@ -236,7 +237,7 @@ int main(int argc, char *argv[]) {
// interpolate charuco corners
Mat currentCharucoCorners, currentCharucoIds;
if(ids.size() > 0)
aruco::interpolateCornersCharuco(corners, ids, image, board, currentCharucoCorners,
aruco::interpolateCornersCharuco(corners, ids, image, charucoboard, currentCharucoCorners,
currentCharucoIds);
// draw results
......@@ -305,7 +306,7 @@ int main(int argc, char *argv[]) {
for(int i = 0; i < nFrames; i++) {
// interpolate using camera parameters
Mat currentCharucoCorners, currentCharucoIds;
aruco::interpolateCornersCharuco(allCorners[i], allIds[i], allImgs[i], board,
aruco::interpolateCornersCharuco(allCorners[i], allIds[i], allImgs[i], charucoboard,
currentCharucoCorners, currentCharucoIds, cameraMatrix,
distCoeffs);
......@@ -321,7 +322,7 @@ int main(int argc, char *argv[]) {
// calibrate camera using charuco
repError =
aruco::calibrateCameraCharuco(allCharucoCorners, allCharucoIds, board, imgSize,
aruco::calibrateCameraCharuco(allCharucoCorners, allCharucoIds, charucoboard, imgSize,
cameraMatrix, distCoeffs, rvecs, tvecs, calibrationFlags);
bool saveOk = saveCameraParams(outputFile, imgSize, aspectRatio, calibrationFlags,
......
......@@ -93,15 +93,15 @@ int main(int argc, char *argv[]) {
imageSize.height =
markersY * (markerLength + markerSeparation) - markerSeparation + 2 * margins;
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
aruco::GridBoard board = aruco::GridBoard::create(markersX, markersY, float(markerLength),
Ptr<aruco::GridBoard> board = aruco::GridBoard::create(markersX, markersY, float(markerLength),
float(markerSeparation), dictionary);
// show created board
Mat boardImage;
board.draw(imageSize, boardImage, margins, borderBits);
board->draw(imageSize, boardImage, margins, borderBits);
if(showImage) {
imshow("board", boardImage);
......
......@@ -88,19 +88,19 @@ int main(int argc, char *argv[]) {
return 0;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
Size imageSize;
imageSize.width = squaresX * squareLength + 2 * margins;
imageSize.height = squaresY * squareLength + 2 * margins;
aruco::CharucoBoard board = aruco::CharucoBoard::create(squaresX, squaresY, (float)squareLength,
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(squaresX, squaresY, (float)squareLength,
(float)markerLength, dictionary);
// show created board
Mat boardImage;
board.draw(imageSize, boardImage, margins, borderBits);
board->draw(imageSize, boardImage, margins, borderBits);
if(showImage) {
imshow("board", boardImage);
......
......@@ -86,7 +86,7 @@ int main(int argc, char *argv[]) {
return 0;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
istringstream ss(idsString);
......
......@@ -79,7 +79,7 @@ int main(int argc, char *argv[]) {
return 0;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
Mat markerImg;
......
......@@ -79,30 +79,30 @@ static bool readCameraParameters(string filename, Mat &camMatrix, Mat &distCoeff
/**
*/
static bool readDetectorParameters(string filename, aruco::DetectorParameters &params) {
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["doCornerRefinement"] >> params.doCornerRefinement;
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;
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["doCornerRefinement"] >> params->doCornerRefinement;
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;
}
......@@ -137,7 +137,7 @@ int main(int argc, char *argv[]) {
}
}
aruco::DetectorParameters detectorParams;
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
if(!readOk) {
......@@ -145,7 +145,7 @@ int main(int argc, char *argv[]) {
return 0;
}
}
detectorParams.doCornerRefinement = true; // do corner refinement in markers
detectorParams->doCornerRefinement = true; // do corner refinement in markers
String video;
if(parser.has("v")) {
......@@ -157,7 +157,7 @@ int main(int argc, char *argv[]) {
return 0;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
VideoCapture inputVideo;
......@@ -174,8 +174,9 @@ int main(int argc, char *argv[]) {
markerSeparation);
// create board object
aruco::GridBoard board =
Ptr<aruco::GridBoard> gridboard =
aruco::GridBoard::create(markersX, markersY, markerLength, markerSeparation, dictionary);
Ptr<aruco::Board> board = gridboard.staticCast<aruco::Board>();
double totalTime = 0;
int totalIterations = 0;
......
......@@ -79,30 +79,30 @@ static bool readCameraParameters(string filename, Mat &camMatrix, Mat &distCoeff
/**
*/
static bool readDetectorParameters(string filename, aruco::DetectorParameters &params) {
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["doCornerRefinement"] >> params.doCornerRefinement;
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;
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["doCornerRefinement"] >> params->doCornerRefinement;
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;
}
......@@ -141,7 +141,7 @@ int main(int argc, char *argv[]) {
}
}
aruco::DetectorParameters detectorParams;
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
if(!readOk) {
......@@ -155,7 +155,7 @@ int main(int argc, char *argv[]) {
return 0;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
VideoCapture inputVideo;
......@@ -171,8 +171,9 @@ int main(int argc, char *argv[]) {
float axisLength = 0.5f * ((float)min(squaresX, squaresY) * (squareLength));
// create charuco board object
aruco::CharucoBoard board =
Ptr<aruco::CharucoBoard> charucoboard =
aruco::CharucoBoard::create(squaresX, squaresY, squareLength, markerLength, dictionary);
Ptr<aruco::Board> board = charucoboard.staticCast<aruco::Board>();
double totalTime = 0;
int totalIterations = 0;
......@@ -201,13 +202,13 @@ int main(int argc, char *argv[]) {
int interpolatedCorners = 0;
if(markerIds.size() > 0)
interpolatedCorners =
aruco::interpolateCornersCharuco(markerCorners, markerIds, image, board,
aruco::interpolateCornersCharuco(markerCorners, markerIds, image, charucoboard,
charucoCorners, charucoIds, camMatrix, distCoeffs);
// estimate charuco board pose
bool validPose = false;
if(camMatrix.total() != 0)
validPose = aruco::estimatePoseCharucoBoard(charucoCorners, charucoIds, board,
validPose = aruco::estimatePoseCharucoBoard(charucoCorners, charucoIds, charucoboard,
camMatrix, distCoeffs, rvec, tvec);
......
......@@ -80,30 +80,30 @@ static bool readCameraParameters(string filename, Mat &camMatrix, Mat &distCoeff
/**
*/
static bool readDetectorParameters(string filename, aruco::DetectorParameters &params) {
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["doCornerRefinement"] >> params.doCornerRefinement;
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;
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["doCornerRefinement"] >> params->doCornerRefinement;
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;
}
......@@ -127,7 +127,7 @@ int main(int argc, char *argv[]) {
bool autoScale = parser.has("as");
float autoScaleFactor = autoScale ? parser.get<float>("as") : 1.f;
aruco::DetectorParameters detectorParams;
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
if(!readOk) {
......@@ -148,7 +148,7 @@ int main(int argc, char *argv[]) {
return 0;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
Mat camMatrix, distCoeffs;
......
......@@ -74,30 +74,30 @@ static bool readCameraParameters(string filename, Mat &camMatrix, Mat &distCoeff
/**
*/
static bool readDetectorParameters(string filename, aruco::DetectorParameters &params) {
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["doCornerRefinement"] >> params.doCornerRefinement;
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;
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["doCornerRefinement"] >> params->doCornerRefinement;
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;
}
......@@ -119,7 +119,7 @@ int main(int argc, char *argv[]) {
bool estimatePose = parser.has("c");
float markerLength = parser.get<float>("l");
aruco::DetectorParameters detectorParams;
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
if(parser.has("dp")) {
bool readOk = readDetectorParameters(parser.get<string>("dp"), detectorParams);
if(!readOk) {
......@@ -127,7 +127,7 @@ int main(int argc, char *argv[]) {
return 0;
}
}
detectorParams.doCornerRefinement = true; // do corner refinement in markers
detectorParams->doCornerRefinement = true; // do corner refinement in markers
int camId = parser.get<int>("ci");
......@@ -141,7 +141,7 @@ int main(int argc, char *argv[]) {
return 0;
}
aruco::Dictionary dictionary =
Ptr<aruco::Dictionary> dictionary =
aruco::getPredefinedDictionary(aruco::PREDEFINED_DICTIONARY_NAME(dictionaryId));
Mat camMatrix, distCoeffs;
......
This diff is collapsed.
This diff is collapsed.
......@@ -48,6 +48,16 @@ namespace aruco {
using namespace std;
/**
*/
Dictionary::Dictionary(const Ptr<Dictionary> &_dictionary) {
markerSize = _dictionary->markerSize;
maxCorrectionBits = _dictionary->maxCorrectionBits;
bytesList = _dictionary->bytesList.clone();
}
/**
*/
Dictionary::Dictionary(const Mat &_bytesList, int _markerSize, int _maxcorr) {
......@@ -57,6 +67,28 @@ Dictionary::Dictionary(const Mat &_bytesList, int _markerSize, int _maxcorr) {
}
/**
*/
Ptr<Dictionary> Dictionary::create(int nMarkers, int markerSize) {
Ptr<Dictionary> baseDictionary = makePtr<Dictionary>();
return create(nMarkers, markerSize, baseDictionary);
}
/**
*/
Ptr<Dictionary> Dictionary::create(int nMarkers, int markerSize,
Ptr<Dictionary> &baseDictionary) {
return generateCustomDictionary(nMarkers, markerSize, baseDictionary);
}
/**
*/
Ptr<Dictionary> Dictionary::get(int dict) {
return getPredefinedDictionary(dict);
}
/**
*/
......@@ -259,50 +291,55 @@ const Dictionary DICT_7X7_250_DATA = Dictionary(Mat(250, (7*7 + 7)/8 ,CV_8UC4, (
const Dictionary DICT_7X7_1000_DATA = Dictionary(Mat(1000, (7*7 + 7)/8 ,CV_8UC4, (uchar*)DICT_7X7_1000_BYTES), 7, 6);
const Dictionary &getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name) {
Ptr<Dictionary> getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME name) {
switch(name) {
case DICT_ARUCO_ORIGINAL:
return DICT_ARUCO_DATA;
return makePtr<Dictionary>(DICT_ARUCO_DATA);
case DICT_4X4_50:
return DICT_4X4_50_DATA;
return makePtr<Dictionary>(DICT_4X4_50_DATA);
case DICT_4X4_100:
return DICT_4X4_100_DATA;
return makePtr<Dictionary>(DICT_4X4_100_DATA);
case DICT_4X4_250:
return DICT_4X4_250_DATA;
return makePtr<Dictionary>(DICT_4X4_250_DATA);
case DICT_4X4_1000:
return DICT_4X4_1000_DATA;
return makePtr<Dictionary>(DICT_4X4_1000_DATA);
case DICT_5X5_50:
return DICT_5X5_50_DATA;
return makePtr<Dictionary>(DICT_5X5_50_DATA);
case DICT_5X5_100:
return DICT_5X5_100_DATA;
return makePtr<Dictionary>(DICT_5X5_100_DATA);
case DICT_5X5_250:
return DICT_5X5_250_DATA;
return makePtr<Dictionary>(DICT_5X5_250_DATA);
case DICT_5X5_1000:
return DICT_5X5_1000_DATA;
return makePtr<Dictionary>(DICT_5X5_1000_DATA);
case DICT_6X6_50:
return DICT_6X6_50_DATA;
return makePtr<Dictionary>(DICT_6X6_50_DATA);
case DICT_6X6_100:
return DICT_6X6_100_DATA;
return makePtr<Dictionary>(DICT_6X6_100_DATA);
case DICT_6X6_250:
return DICT_6X6_250_DATA;
return makePtr<Dictionary>(DICT_6X6_250_DATA);
case DICT_6X6_1000:
return DICT_6X6_1000_DATA;
return makePtr<Dictionary>(DICT_6X6_1000_DATA);
case DICT_7X7_50:
return DICT_7X7_50_DATA;
return makePtr<Dictionary>(DICT_7X7_50_DATA);
case DICT_7X7_100:
return DICT_7X7_100_DATA;
return makePtr<Dictionary>(DICT_7X7_100_DATA);
case DICT_7X7_250:
return DICT_7X7_250_DATA;
return makePtr<Dictionary>(DICT_7X7_250_DATA);
case DICT_7X7_1000:
return DICT_7X7_1000_DATA;
return makePtr<Dictionary>(DICT_7X7_1000_DATA);
}
return DICT_4X4_50_DATA;
return makePtr<Dictionary>(DICT_4X4_50_DATA);
}
Ptr<Dictionary> getPredefinedDictionary(int dict) {
return getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME(dict));
}
......@@ -339,11 +376,11 @@ static int _getSelfDistance(const Mat &marker) {
/**
*/
Dictionary generateCustomDictionary(int nMarkers, int markerSize,
const Dictionary &baseDictionary) {
Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize,
Ptr<Dictionary> &baseDictionary) {
Dictionary out;
out.markerSize = markerSize;
Ptr<Dictionary> out = makePtr<Dictionary>();
out->markerSize = markerSize;
// theoretical maximum intermarker distance
// See S. Garrido-Jurado, R. Muñoz-Salinas, F. J. Madrid-Cuevas, and M. J. Marín-Jiménez. 2014.
......@@ -353,17 +390,17 @@ Dictionary generateCustomDictionary(int nMarkers, int markerSize,
int tau = 2 * (int)std::floor(float(C) * 4.f / 3.f);
// if baseDictionary is provided, calculate its intermarker distance
if(baseDictionary.bytesList.rows > 0) {
CV_Assert(baseDictionary.markerSize == markerSize);
out.bytesList = baseDictionary.bytesList.clone();
if(baseDictionary->bytesList.rows > 0) {
CV_Assert(baseDictionary->markerSize == markerSize);
out->bytesList = baseDictionary->bytesList.clone();
int minDistance = markerSize * markerSize + 1;
for(int i = 0; i < out.bytesList.rows; i++) {
Mat markerBytes = out.bytesList.rowRange(i, i + 1);
for(int i = 0; i < out->bytesList.rows; i++) {
Mat markerBytes = out->bytesList.rowRange(i, i + 1);
Mat markerBits = Dictionary::getBitsFromByteList(markerBytes, markerSize);
minDistance = min(minDistance, _getSelfDistance(markerBits));
for(int j = i + 1; j < out.bytesList.rows; j++) {
minDistance = min(minDistance, out.getDistanceToId(markerBits, j));
for(int j = i + 1; j < out->bytesList.rows; j++) {
minDistance = min(minDistance, out->getDistanceToId(markerBits, j));
}
}
tau = minDistance;
......@@ -377,7 +414,7 @@ Dictionary generateCustomDictionary(int nMarkers, int markerSize,
const int maxUnproductiveIterations = 5000;
int unproductiveIterations = 0;
while(out.bytesList.rows < nMarkers) {
while(out->bytesList.rows < nMarkers) {
Mat currentMarker = _generateRandomMarker(markerSize);
int selfDistance = _getSelfDistance(currentMarker);
......@@ -386,8 +423,8 @@ Dictionary generateCustomDictionary(int nMarkers, int markerSize,
// if self distance is better or equal than current best option, calculate distance
// to previous accepted markers
if(selfDistance >= bestTau) {
for(int i = 0; i < out.bytesList.rows; i++) {
int currentDistance = out.getDistanceToId(currentMarker, i);
for(int i = 0; i < out->bytesList.rows; i++) {
int currentDistance = out->getDistanceToId(currentMarker, i);
minDistance = min(currentDistance, minDistance);
if(minDistance <= bestTau) {
break;
......@@ -400,7 +437,7 @@ Dictionary generateCustomDictionary(int nMarkers, int markerSize,
unproductiveIterations = 0;
bestTau = 0;
Mat bytes = Dictionary::getByteListFromBits(currentMarker);
out.bytesList.push_back(bytes);
out->bytesList.push_back(bytes);
} else {
unproductiveIterations++;
......@@ -416,15 +453,25 @@ Dictionary generateCustomDictionary(int nMarkers, int markerSize,
tau = bestTau;
bestTau = 0;
Mat bytes = Dictionary::getByteListFromBits(bestMarker);
out.bytesList.push_back(bytes);
out->bytesList.push_back(bytes);
}
}
}
// update the maximum number of correction bits for the generated dictionary
out.maxCorrectionBits = (tau - 1) / 2;
out->maxCorrectionBits = (tau - 1) / 2;
return out;
}
/**
*/
Ptr<Dictionary> generateCustomDictionary(int nMarkers, int markerSize) {
Ptr<Dictionary> baseDictionary = makePtr<Dictionary>();
return generateCustomDictionary(nMarkers, markerSize, baseDictionary);
}
}
}
......@@ -62,7 +62,7 @@ CV_ArucoDetectionSimple::CV_ArucoDetectionSimple() {}
void CV_ArucoDetectionSimple::run(int) {
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
// 20 images
for(int i = 0; i < 20; i++) {
......@@ -99,7 +99,7 @@ void CV_ArucoDetectionSimple::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::DetectorParameters params;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
aruco::detectMarkers(img, dictionary, corners, ids, params);
// check detection results
......@@ -183,7 +183,7 @@ static void getSyntheticRT(double yaw, double pitch, double distance, Mat &rvec,
/**
* @brief Create a synthetic image of a marker with perspective
*/
static Mat projectMarker(aruco::Dictionary dictionary, int id, Mat cameraMatrix, double yaw,
static Mat projectMarker(Ptr<aruco::Dictionary> &dictionary, int id, Mat cameraMatrix, double yaw,
double pitch, double distance, Size imageSize, int markerBorder,
vector< Point2f > &corners) {
......@@ -257,7 +257,7 @@ void CV_ArucoDetectionPerspective::run(int) {
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
cameraMatrix.at< double >(1, 2) = imgSize.height / 2;
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
// detect from different positions
for(double distance = 0.1; distance <= 0.5; distance += 0.2) {
......@@ -275,9 +275,9 @@ void CV_ArucoDetectionPerspective::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::DetectorParameters params;
params.minDistanceToBorder = 1;
params.markerBorderBits = markerBorder;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 1;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
// check results
......@@ -320,7 +320,7 @@ CV_ArucoDetectionMarkerSize::CV_ArucoDetectionMarkerSize() {}
void CV_ArucoDetectionMarkerSize::run(int) {
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
int markerSide = 20;
int imageSize = 200;
......@@ -337,10 +337,10 @@ void CV_ArucoDetectionMarkerSize::run(int) {
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::DetectorParameters params;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
// set a invalid minMarkerPerimeterRate
params.minMarkerPerimeterRate = min(4., (4. * markerSide) / float(imageSize) + 0.1);
params->minMarkerPerimeterRate = min(4., (4. * markerSide) / float(imageSize) + 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(corners.size() != 0) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::minMarkerPerimeterRate");
......@@ -349,7 +349,7 @@ void CV_ArucoDetectionMarkerSize::run(int) {
}
// set an valid minMarkerPerimeterRate
params.minMarkerPerimeterRate = max(0., (4. * markerSide) / float(imageSize) - 0.1);
params->minMarkerPerimeterRate = max(0., (4. * markerSide) / float(imageSize) - 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(corners.size() != 1 || (corners.size() == 1 && ids[0] != id)) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::minMarkerPerimeterRate");
......@@ -358,7 +358,7 @@ void CV_ArucoDetectionMarkerSize::run(int) {
}
// set a invalid maxMarkerPerimeterRate
params.maxMarkerPerimeterRate = min(4., (4. * markerSide) / float(imageSize) - 0.1);
params->maxMarkerPerimeterRate = min(4., (4. * markerSide) / float(imageSize) - 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(corners.size() != 0) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::maxMarkerPerimeterRate");
......@@ -367,7 +367,7 @@ void CV_ArucoDetectionMarkerSize::run(int) {
}
// set an valid maxMarkerPerimeterRate
params.maxMarkerPerimeterRate = max(0., (4. * markerSide) / float(imageSize) + 0.1);
params->maxMarkerPerimeterRate = max(0., (4. * markerSide) / float(imageSize) + 0.1);
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(corners.size() != 1 || (corners.size() == 1 && ids[0] != id)) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::maxMarkerPerimeterRate");
......@@ -395,11 +395,12 @@ CV_ArucoBitCorrection::CV_ArucoBitCorrection() {}
void CV_ArucoBitCorrection::run(int) {
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::Dictionary dictionary2 = dictionary;
Ptr<aruco::Dictionary> _dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::Dictionary &dictionary = *_dictionary;
aruco::Dictionary dictionary2 = *_dictionary;
int markerSide = 50;
int imageSize = 150;
aruco::DetectorParameters params;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
// 10 markers
for(int l = 0; l < 10; l++) {
......@@ -411,9 +412,9 @@ void CV_ArucoBitCorrection::run(int) {
// 5 valid cases
for(int i = 0; i < 5; i++) {
// how many bit errors (the error is low enough so it can be corrected)
params.errorCorrectionRate = 0.2 + i * 0.1;
params->errorCorrectionRate = 0.2 + i * 0.1;
int errors =
(int)std::floor(dictionary.maxCorrectionBits * params.errorCorrectionRate - 1.);
(int)std::floor(dictionary.maxCorrectionBits * params->errorCorrectionRate - 1.);
// create erroneous marker in currentCodeBits
Mat currentCodeBits =
......@@ -427,14 +428,14 @@ void CV_ArucoBitCorrection::run(int) {
Mat currentCodeBytesError = aruco::Dictionary::getByteListFromBits(currentCodeBits);
currentCodeBytesError.copyTo(dictionary2.bytesList.rowRange(id, id + 1));
Mat img = Mat(imageSize, imageSize, CV_8UC1, Scalar::all(255));
aruco::drawMarker(dictionary2, id, markerSide, marker);
dictionary2.drawMarker(id, markerSide, marker);
Mat aux = img.colRange(30, 30 + markerSide).rowRange(50, 50 + markerSide);
marker.copyTo(aux);
// try to detect using original dictionary
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::detectMarkers(img, dictionary, corners, ids, params);
aruco::detectMarkers(img, _dictionary, corners, ids, params);
if(corners.size() != 1 || (corners.size() == 1 && ids[0] != id)) {
ts->printf(cvtest::TS::LOG, "Error in bit correction");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
......@@ -445,9 +446,9 @@ void CV_ArucoBitCorrection::run(int) {
// 5 invalid cases
for(int i = 0; i < 5; i++) {
// how many bit errors (the error is too high to be corrected)
params.errorCorrectionRate = 0.2 + i * 0.1;
params->errorCorrectionRate = 0.2 + i * 0.1;
int errors =
(int)std::floor(dictionary.maxCorrectionBits * params.errorCorrectionRate + 1.);
(int)std::floor(dictionary.maxCorrectionBits * params->errorCorrectionRate + 1.);
// create erroneous marker in currentCodeBits
Mat currentCodeBits =
......@@ -458,21 +459,23 @@ void CV_ArucoBitCorrection::run(int) {
}
// dictionary3 is only composed by the modified marker (in its original form)
aruco::Dictionary dictionary3 = dictionary;
dictionary3.bytesList = dictionary2.bytesList.rowRange(id, id + 1).clone();
Ptr<aruco::Dictionary> _dictionary3 = makePtr<aruco::Dictionary>(
dictionary2.bytesList.rowRange(id, id + 1).clone(),
dictionary.markerSize,
dictionary.maxCorrectionBits);
// add erroneous marker to dictionary2 in order to create the erroneous marker image
Mat currentCodeBytesError = aruco::Dictionary::getByteListFromBits(currentCodeBits);
currentCodeBytesError.copyTo(dictionary2.bytesList.rowRange(id, id + 1));
Mat img = Mat(imageSize, imageSize, CV_8UC1, Scalar::all(255));
aruco::drawMarker(dictionary2, id, markerSide, marker);
dictionary2.drawMarker(id, markerSide, marker);
Mat aux = img.colRange(30, 30 + markerSide).rowRange(50, 50 + markerSide);
marker.copyTo(aux);
// try to detect using dictionary3, it should fail
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::detectMarkers(img, dictionary3, corners, ids, params);
aruco::detectMarkers(img, _dictionary3, corners, ids, params);
if(corners.size() != 0) {
ts->printf(cvtest::TS::LOG, "Error in DetectorParameters::errorCorrectionRate");
ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY);
......
......@@ -98,7 +98,7 @@ static void getSyntheticRT(double yaw, double pitch, double distance, Mat &rvec,
/**
* @brief Project a synthetic marker
*/
static void projectMarker(Mat &img, aruco::Dictionary dictionary, int id,
static void projectMarker(Mat &img, Ptr<aruco::Dictionary> &dictionary, int id,
vector< Point3f > markerObjPoints, Mat cameraMatrix, Mat rvec, Mat tvec,
int markerBorder) {
......@@ -140,15 +140,15 @@ static void projectMarker(Mat &img, aruco::Dictionary dictionary, int id,
/**
* @brief Get a synthetic image of GridBoard in perspective
*/
static Mat projectBoard(aruco::GridBoard board, Mat cameraMatrix, double yaw, double pitch,
static Mat projectBoard(Ptr<aruco::GridBoard> &board, Mat cameraMatrix, double yaw, double pitch,
double distance, Size imageSize, int markerBorder) {
Mat rvec, tvec;
getSyntheticRT(yaw, pitch, distance, rvec, tvec);
Mat img = Mat(imageSize, CV_8UC1, Scalar::all(255));
for(unsigned int m = 0; m < board.ids.size(); m++) {
projectMarker(img, board.dictionary, board.ids[m], board.objPoints[m], cameraMatrix, rvec,
for(unsigned int m = 0; m < board->ids.size(); m++) {
projectMarker(img, board->dictionary, board->ids[m], board->objPoints[m], cameraMatrix, rvec,
tvec, markerBorder);
}
......@@ -177,8 +177,9 @@ void CV_ArucoBoardPose::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::GridBoard board = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, dictionary);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::GridBoard> gridboard = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, dictionary);
Ptr<aruco::Board> board = gridboard.staticCast<aruco::Board>();
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
cameraMatrix.at< double >(1, 2) = imgSize.height / 2;
......@@ -188,21 +189,21 @@ void CV_ArucoBoardPose::run(int) {
for(double distance = 0.2; distance <= 0.4; distance += 0.2) {
for(int yaw = 0; yaw < 360; yaw += 100) {
for(int pitch = 30; pitch <= 90; pitch += 50) {
for(unsigned int i = 0; i < board.ids.size(); i++)
board.ids[i] = (iter + int(i)) % 250;
for(unsigned int i = 0; i < gridboard->ids.size(); i++)
gridboard->ids[i] = (iter + int(i)) % 250;
int markerBorder = iter % 2 + 1;
iter++;
// create synthetic image
Mat img = projectBoard(board, cameraMatrix, deg2rad(pitch), deg2rad(yaw), distance,
Mat img = projectBoard(gridboard, cameraMatrix, deg2rad(pitch), deg2rad(yaw), distance,
imgSize, markerBorder);
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::DetectorParameters params;
params.minDistanceToBorder = 3;
params.markerBorderBits = markerBorder;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(ids.size() == 0) {
......@@ -218,8 +219,8 @@ void CV_ArucoBoardPose::run(int) {
// check result
for(unsigned int i = 0; i < ids.size(); i++) {
int foundIdx = -1;
for(unsigned int j = 0; j < board.ids.size(); j++) {
if(board.ids[j] == ids[i]) {
for(unsigned int j = 0; j < gridboard->ids.size(); j++) {
if(gridboard->ids[j] == ids[i]) {
foundIdx = int(j);
break;
}
......@@ -232,7 +233,7 @@ void CV_ArucoBoardPose::run(int) {
}
vector< Point2f > projectedCorners;
projectPoints(board.objPoints[foundIdx], rvec, tvec, cameraMatrix, distCoeffs,
projectPoints(gridboard->objPoints[foundIdx], rvec, tvec, cameraMatrix, distCoeffs,
projectedCorners);
for(int c = 0; c < 4; c++) {
......@@ -271,8 +272,9 @@ void CV_ArucoRefine::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::GridBoard board = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, dictionary);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::GridBoard> gridboard = aruco::GridBoard::create(3, 3, 0.02f, 0.005f, dictionary);
Ptr<aruco::Board> board = gridboard.staticCast<aruco::Board>();
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
cameraMatrix.at< double >(1, 2) = imgSize.height / 2;
......@@ -282,23 +284,23 @@ void CV_ArucoRefine::run(int) {
for(double distance = 0.2; distance <= 0.4; distance += 0.2) {
for(int yaw = 0; yaw < 360; yaw += 100) {
for(int pitch = 30; pitch <= 90; pitch += 50) {
for(unsigned int i = 0; i < board.ids.size(); i++)
board.ids[i] = (iter + int(i)) % 250;
for(unsigned int i = 0; i < gridboard->ids.size(); i++)
gridboard->ids[i] = (iter + int(i)) % 250;
int markerBorder = iter % 2 + 1;
iter++;
// create synthetic image
Mat img = projectBoard(board, cameraMatrix, deg2rad(pitch), deg2rad(yaw), distance,
Mat img = projectBoard(gridboard, cameraMatrix, deg2rad(pitch), deg2rad(yaw), distance,
imgSize, markerBorder);
// detect markers
vector< vector< Point2f > > corners, rejected;
vector< int > ids;
aruco::DetectorParameters params;
params.minDistanceToBorder = 3;
params.doCornerRefinement = true;
params.markerBorderBits = markerBorder;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
params->doCornerRefinement = true;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params, rejected);
// remove a marker from detection
......
......@@ -98,7 +98,7 @@ static void getSyntheticRT(double yaw, double pitch, double distance, Mat &rvec,
/**
* @brief Project a synthetic marker
*/
static void projectMarker(Mat &img, aruco::Dictionary dictionary, int id,
static void projectMarker(Mat &img, Ptr<aruco::Dictionary> dictionary, int id,
vector< Point3f > markerObjPoints, Mat cameraMatrix, Mat rvec, Mat tvec,
int markerBorder) {
......@@ -176,7 +176,7 @@ static Mat projectChessboard(int squaresX, int squaresY, float squareSize, Size
/**
* @brief Check pose estimation of charuco board
*/
static Mat projectCharucoBoard(aruco::CharucoBoard board, Mat cameraMatrix, double yaw,
static Mat projectCharucoBoard(Ptr<aruco::CharucoBoard> &board, Mat cameraMatrix, double yaw,
double pitch, double distance, Size imageSize, int markerBorder,
Mat &rvec, Mat &tvec) {
......@@ -184,15 +184,15 @@ static Mat projectCharucoBoard(aruco::CharucoBoard board, Mat cameraMatrix, doub
// project markers
Mat img = Mat(imageSize, CV_8UC1, Scalar::all(255));
for(unsigned int m = 0; m < board.ids.size(); m++) {
projectMarker(img, board.dictionary, board.ids[m], board.objPoints[m], cameraMatrix, rvec,
for(unsigned int m = 0; m < board->ids.size(); m++) {
projectMarker(img, board->dictionary, board->ids[m], board->objPoints[m], cameraMatrix, rvec,
tvec, markerBorder);
}
// project chessboard
Mat chessboard =
projectChessboard(board.getChessboardSize().width, board.getChessboardSize().height,
board.getSquareLength(), imageSize, cameraMatrix, rvec, tvec);
projectChessboard(board->getChessboardSize().width, board->getChessboardSize().height,
board->getSquareLength(), imageSize, cameraMatrix, rvec, tvec);
for(unsigned int i = 0; i < chessboard.total(); i++) {
if(chessboard.ptr< unsigned char >()[i] == 0) {
......@@ -226,8 +226,8 @@ void CV_CharucoDetection::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::CharucoBoard board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, dictionary);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, dictionary);
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
......@@ -251,9 +251,9 @@ void CV_CharucoDetection::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::DetectorParameters params;
params.minDistanceToBorder = 3;
params.markerBorderBits = markerBorder;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(ids.size() == 0) {
......@@ -276,14 +276,14 @@ void CV_CharucoDetection::run(int) {
// check results
vector< Point2f > projectedCharucoCorners;
projectPoints(board.chessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectPoints(board->chessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectedCharucoCorners);
for(unsigned int i = 0; i < charucoIds.size(); i++) {
int currentId = charucoIds[i];
if(currentId >= (int)board.chessboardCorners.size()) {
if(currentId >= (int)board->chessboardCorners.size()) {
ts->printf(cvtest::TS::LOG, "Invalid Charuco corner id");
ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
return;
......@@ -325,8 +325,8 @@ void CV_CharucoPoseEstimation::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
aruco::CharucoBoard board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, dictionary);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::CharucoBoard> board = aruco::CharucoBoard::create(4, 4, 0.03f, 0.015f, dictionary);
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
cameraMatrix.at< double >(0, 2) = imgSize.width / 2;
......@@ -349,9 +349,9 @@ void CV_CharucoPoseEstimation::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::DetectorParameters params;
params.minDistanceToBorder = 3;
params.markerBorderBits = markerBorder;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 3;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(ids.size() == 0) {
......@@ -381,14 +381,14 @@ void CV_CharucoPoseEstimation::run(int) {
// check result
vector< Point2f > projectedCharucoCorners;
projectPoints(board.chessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectPoints(board->chessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectedCharucoCorners);
for(unsigned int i = 0; i < charucoIds.size(); i++) {
int currentId = charucoIds[i];
if(currentId >= (int)board.chessboardCorners.size()) {
if(currentId >= (int)board->chessboardCorners.size()) {
ts->printf(cvtest::TS::LOG, "Invalid Charuco corner id");
ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
return;
......@@ -429,10 +429,10 @@ void CV_CharucoDiamondDetection::run(int) {
int iter = 0;
Mat cameraMatrix = Mat::eye(3, 3, CV_64FC1);
Size imgSize(500, 500);
aruco::Dictionary dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
Ptr<aruco::Dictionary> dictionary = aruco::getPredefinedDictionary(aruco::DICT_6X6_250);
float squareLength = 0.03f;
float markerLength = 0.015f;
aruco::CharucoBoard board =
Ptr<aruco::CharucoBoard> board =
aruco::CharucoBoard::create(3, 3, squareLength, markerLength, dictionary);
cameraMatrix.at< double >(0, 0) = cameraMatrix.at< double >(1, 1) = 650;
......@@ -447,7 +447,7 @@ void CV_CharucoDiamondDetection::run(int) {
int markerBorder = iter % 2 + 1;
for(int i = 0; i < 4; i++)
board.ids[i] = 4 * iter + i;
board->ids[i] = 4 * iter + i;
iter++;
// get synthetic image
......@@ -458,9 +458,9 @@ void CV_CharucoDiamondDetection::run(int) {
// detect markers
vector< vector< Point2f > > corners;
vector< int > ids;
aruco::DetectorParameters params;
params.minDistanceToBorder = 0;
params.markerBorderBits = markerBorder;
Ptr<aruco::DetectorParameters> params = aruco::DetectorParameters::create();
params->minDistanceToBorder = 0;
params->markerBorderBits = markerBorder;
aruco::detectMarkers(img, dictionary, corners, ids, params);
if(ids.size() != 4) {
......@@ -483,7 +483,7 @@ void CV_CharucoDiamondDetection::run(int) {
}
for(int i = 0; i < 4; i++) {
if(diamondIds[0][i] != board.ids[i]) {
if(diamondIds[0][i] != board->ids[i]) {
ts->printf(cvtest::TS::LOG, "Incorrect diamond ids");
ts->set_failed_test_info(cvtest::TS::FAIL_MISMATCH);
return;
......@@ -492,7 +492,7 @@ void CV_CharucoDiamondDetection::run(int) {
vector< Point2f > projectedDiamondCorners;
projectPoints(board.chessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectPoints(board->chessboardCorners, rvec, tvec, cameraMatrix, distCoeffs,
projectedDiamondCorners);
vector< Point2f > projectedDiamondCornersReorder(4);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment