Skip to content

Commit

Permalink
add set/get/dictionary/objPoints, update tests
Browse files Browse the repository at this point in the history
  • Loading branch information
AleksandrPanov committed Aug 3, 2022
1 parent 1f003fe commit 230b6c9
Show file tree
Hide file tree
Showing 11 changed files with 200 additions and 121 deletions.
38 changes: 34 additions & 4 deletions modules/aruco/include/opencv2/aruco/board.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,36 @@ class CV_EXPORTS_W Board {
*/
CV_WRAP void setIds(InputArray ids);

/** @brief change id for ids[index]
* @param index - element index in ids
* @param newId - new value for ids[index], should be less than Dictionary size
*/
CV_WRAP void changeId(int index, int newId);
/** @brief return ids
*/
CV_WRAP const std::vector<int>& getIds() const;

/** @brief set dictionary
*/
CV_WRAP void setDictionary(const Ptr<Dictionary> &dictionary);

/** @brief return dictionary
*/
CV_WRAP Ptr<Dictionary> getDictionary() const;

/** @brief set objPoints
*/
CV_WRAP void setObjPoints(const std::vector<std::vector<Point3f> > &objPoints);

/** @brief get objPoints
*/
CV_WRAP const std::vector<std::vector<Point3f> >& getObjPoints() const;

/** @brief get rightBottomBorder
*/
CV_WRAP const Point3f& getRightBottomBorder() const;

protected:
/** @brief array of object points of all the marker corners in the board each marker include its 4 corners in this order:
* - objPoints[i][0] - left-top point of i-th marker
* - objPoints[i][1] - right-top point of i-th marker
Expand All @@ -58,13 +88,13 @@ class CV_EXPORTS_W Board {
/// the dictionary of markers employed for this board
CV_PROP Ptr<Dictionary> dictionary;

/// coordinate of the bottom right corner of the board, is set when calling the function create()
CV_PROP Point3f rightBottomBorder;

/** @brief vector of the identifiers of the markers in the board (same size than objPoints)
* The identifiers refers to the board dictionary
*/
CV_PROP_RW std::vector<int> ids;

/// coordinate of the bottom right corner of the board, is set when calling the function create()
CV_PROP Point3f rightBottomBorder;
};

/**
Expand Down Expand Up @@ -196,7 +226,7 @@ class CV_EXPORTS_W CharucoBoard : public Board {
* @param board layout of ChArUco board.
* @param charucoIds list of identifiers for each corner in charucoCorners per frame.
* @return bool value, 1 (true) if detected corners form a line, 0 (false) if they do not.
solvePnP, calibration functions will fail if the corners are collinear (true).
* solvePnP, calibration functions will fail if the corners are collinear (true).
*
* The number of ids in charucoIDs should be <= the number of chessboard corners in the board.
* This functions checks whether the charuco corners are on a straight line (returns true, if so), or not (false).
Expand Down
8 changes: 4 additions & 4 deletions modules/aruco/misc/python/test/test_aruco.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,13 @@ def test_idsAccessibility(self):
aruco_dict = cv.aruco.Dictionary_get(cv.aruco.DICT_5X5_250)
board = cv.aruco.CharucoBoard_create(7, 5, 1, 0.5, aruco_dict)

np.testing.assert_array_equal(board.ids.squeeze(), ids)
np.testing.assert_array_equal(board.getIds().squeeze(), ids)

board.ids = rev_ids
np.testing.assert_array_equal(board.ids.squeeze(), rev_ids)
board.setIds(rev_ids)
np.testing.assert_array_equal(board.getIds().squeeze(), rev_ids)

board.setIds(ids)
np.testing.assert_array_equal(board.ids.squeeze(), ids)
np.testing.assert_array_equal(board.getIds().squeeze(), ids)

with self.assertRaises(cv.error):
board.setIds(np.array([0]))
Expand Down
4 changes: 2 additions & 2 deletions modules/aruco/samples/tutorial_charuco_create_detect.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ static inline void detectCharucoBoardWithCalibrationPose()
//! [midcornerdet]
std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f> > markerCorners;
cv::aruco::detectMarkers(image, board->dictionary, markerCorners, markerIds, params);
cv::aruco::detectMarkers(image, board->getDictionary(), markerCorners, markerIds, params);
//! [midcornerdet]
// if at least one marker detected
if (markerIds.size() > 0) {
Expand Down Expand Up @@ -100,7 +100,7 @@ static inline void detectCharucoBoardWithoutCalibration()
image.copyTo(imageCopy);
std::vector<int> markerIds;
std::vector<std::vector<cv::Point2f> > markerCorners;
cv::aruco::detectMarkers(image, board->dictionary, markerCorners, markerIds, params);
cv::aruco::detectMarkers(image, board->getDictionary(), markerCorners, markerIds, params);
//or
//cv::aruco::detectMarkers(image, dictionary, markerCorners, markerIds, params);
// if at least one marker detected
Expand Down
2 changes: 1 addition & 1 deletion modules/aruco/src/aruco.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ void refineDetectedMarkers(InputArray _image, const Ptr<Board> &_board,
bool checkAllOrders, OutputArray _recoveredIdxs,
const Ptr<DetectorParameters> &_params) {
Ptr<RefineParameters> refineParams = RefineParameters::create(minRepDistance, errorCorrectionRate, checkAllOrders);
ArucoDetector detector(_board->dictionary, _params, refineParams);
ArucoDetector detector(_board->getDictionary(), _params, refineParams);
detector.refineDetectedMarkers(_image, _board, _detectedCorners, _detectedIds, _rejectedCorners, _cameraMatrix,
_distCoeffs, _recoveredIdxs);
}
Expand Down
8 changes: 4 additions & 4 deletions modules/aruco/src/aruco_calib_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ using namespace std;

void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners, InputArray detectedIds,
OutputArray objPoints, OutputArray imgPoints) {
CV_Assert(board->ids.size() == board->objPoints.size());
CV_Assert(board->getIds().size() == board->getObjPoints().size());
CV_Assert(detectedIds.total() == detectedCorners.total());

size_t nDetectedMarkers = detectedIds.total();
Expand All @@ -24,10 +24,10 @@ void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays de
// look for detected markers that belong to the board and get their information
for(unsigned int i = 0; i < nDetectedMarkers; i++) {
int currentId = detectedIds.getMat().ptr< int >(0)[i];
for(unsigned int j = 0; j < board->ids.size(); j++) {
if(currentId == board->ids[j]) {
for(unsigned int j = 0; j < board->getIds().size(); j++) {
if(currentId == board->getIds()[j]) {
for(int p = 0; p < 4; p++) {
objPnts.push_back(board->objPoints[j][p]);
objPnts.push_back(board->getObjPoints()[j][p]);
imgPnts.push_back(detectedCorners.getMat(i).ptr< Point2f >(0)[p]);
}
}
Expand Down
30 changes: 15 additions & 15 deletions modules/aruco/src/aruco_detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -965,10 +965,10 @@ static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArray
// search undetected markers and project them using the previous pose
vector<vector<Point2f> > undetectedCorners;
vector<int> undetectedIds;
for(unsigned int i = 0; i < _board->ids.size(); i++) {
for(unsigned int i = 0; i < _board->getIds().size(); i++) {
int foundIdx = -1;
for(unsigned int j = 0; j < _detectedIds.total(); j++) {
if(_board->ids[i] == _detectedIds.getMat().ptr< int >()[j]) {
if(_board->getIds()[i] == _detectedIds.getMat().ptr< int >()[j]) {
foundIdx = j;
break;
}
Expand All @@ -977,8 +977,8 @@ static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArray
// not detected
if(foundIdx == -1) {
undetectedCorners.push_back(vector<Point2f >());
undetectedIds.push_back(_board->ids[i]);
projectPoints(_board->objPoints[i], rvec, tvec, _cameraMatrix, _distCoeffs,
undetectedIds.push_back(_board->getIds()[i]);
projectPoints(_board->getObjPoints()[i], rvec, tvec, _cameraMatrix, _distCoeffs,
undetectedCorners.back());
}
}
Expand All @@ -996,12 +996,12 @@ static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArray
vector<vector<Point2f > >& _undetectedMarkersProjectedCorners,
OutputArray _undetectedMarkersIds) {
// check board points are in the same plane, if not, global homography cannot be applied
CV_Assert(_board->objPoints.size() > 0);
CV_Assert(_board->objPoints[0].size() > 0);
float boardZ = _board->objPoints[0][0].z;
for(unsigned int i = 0; i < _board->objPoints.size(); i++) {
for(unsigned int j = 0; j < _board->objPoints[i].size(); j++)
CV_Assert(boardZ == _board->objPoints[i][j].z);
CV_Assert(_board->getObjPoints().size() > 0);
CV_Assert(_board->getObjPoints()[0].size() > 0);
float boardZ = _board->getObjPoints()[0][0].z;
for(unsigned int i = 0; i < _board->getObjPoints().size(); i++) {
for(unsigned int j = 0; j < _board->getObjPoints()[i].size(); j++)
CV_Assert(boardZ == _board->getObjPoints()[i][j].z);
}

vector<Point2f> detectedMarkersObj2DAll; // Object coordinates (without Z) of all the detected
Expand All @@ -1011,14 +1011,14 @@ static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArray
// missing markers in different vectors
vector<int> undetectedMarkersIds; // ids of missing markers
// find markers included in board, and missing markers from board. Fill the previous vectors
for(unsigned int j = 0; j < _board->ids.size(); j++) {
for(unsigned int j = 0; j < _board->getIds().size(); j++) {
bool found = false;
for(unsigned int i = 0; i < _detectedIds.total(); i++) {
if(_detectedIds.getMat().ptr< int >()[i] == _board->ids[j]) {
if(_detectedIds.getMat().ptr< int >()[i] == _board->getIds()[j]) {
for(int c = 0; c < 4; c++) {
imageCornersAll.push_back(_detectedCorners.getMat(i).ptr< Point2f >()[c]);
detectedMarkersObj2DAll.push_back(
Point2f(_board->objPoints[j][c].x, _board->objPoints[j][c].y));
Point2f(_board->getObjPoints()[j][c].x, _board->getObjPoints()[j][c].y));
}
found = true;
break;
Expand All @@ -1028,9 +1028,9 @@ static void _projectUndetectedMarkers(const Ptr<Board> &_board, InputOutputArray
undetectedMarkersObj2D.push_back(vector<Point2f >());
for(int c = 0; c < 4; c++) {
undetectedMarkersObj2D.back().push_back(
Point2f(_board->objPoints[j][c].x, _board->objPoints[j][c].y));
Point2f(_board->getObjPoints()[j][c].x, _board->getObjPoints()[j][c].y));
}
undetectedMarkersIds.push_back(_board->ids[j]);
undetectedMarkersIds.push_back(_board->getIds()[j]);
}
}
if(imageCornersAll.size() == 0) return;
Expand Down
84 changes: 64 additions & 20 deletions modules/aruco/src/board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,17 +22,17 @@ static void _drawPlanarBoardImpl(Board *_board, Size outSize, OutputArray _img,
out.adjustROI(-marginSize, -marginSize, -marginSize, -marginSize);

// calculate max and min values in XY plane
CV_Assert(_board->objPoints.size() > 0);
CV_Assert(_board->getObjPoints().size() > 0);
float minX, maxX, minY, maxY;
minX = maxX = _board->objPoints[0][0].x;
minY = maxY = _board->objPoints[0][0].y;
minX = maxX = _board->getObjPoints()[0][0].x;
minY = maxY = _board->getObjPoints()[0][0].y;

for(unsigned int i = 0; i < _board->objPoints.size(); i++) {
for(unsigned int i = 0; i < _board->getObjPoints().size(); i++) {
for(int j = 0; j < 4; j++) {
minX = min(minX, _board->objPoints[i][j].x);
maxX = max(maxX, _board->objPoints[i][j].x);
minY = min(minY, _board->objPoints[i][j].y);
maxY = max(maxY, _board->objPoints[i][j].y);
minX = min(minX, _board->getObjPoints()[i][j].x);
maxX = max(maxX, _board->getObjPoints()[i][j].x);
minY = min(minY, _board->getObjPoints()[i][j].y);
maxY = max(maxY, _board->getObjPoints()[i][j].y);
}
}

Expand All @@ -55,14 +55,14 @@ static void _drawPlanarBoardImpl(Board *_board, Size outSize, OutputArray _img,
}

// now paint each marker
Dictionary &dictionary = *(_board->dictionary);
Dictionary &dictionary = *(_board->getDictionary());
Mat marker;
Point2f outCorners[3];
Point2f inCorners[3];
for(unsigned int m = 0; m < _board->objPoints.size(); m++) {
for(unsigned int m = 0; m < _board->getObjPoints().size(); m++) {
// transform corners to markerZone coordinates
for(int j = 0; j < 3; j++) {
Point2f pf = Point2f(_board->objPoints[m][j].x, _board->objPoints[m][j].y);
Point2f pf = Point2f(_board->getObjPoints()[m][j].x, _board->getObjPoints()[m][j].y);
// move top left to 0, 0
pf -= Point2f(minX, minY);
pf.x = pf.x / sizeX * float(out.cols);
Expand All @@ -73,7 +73,7 @@ static void _drawPlanarBoardImpl(Board *_board, Size outSize, OutputArray _img,
// get marker
Size dst_sz(outCorners[2] - outCorners[0]); // assuming CCW order
dst_sz.width = dst_sz.height = std::min(dst_sz.width, dst_sz.height); //marker should be square
dictionary.drawMarker(_board->ids[m], dst_sz.width, marker, borderBits);
dictionary.drawMarker(_board->getIds()[m], dst_sz.width, marker, borderBits);

if((outCorners[0].y == outCorners[1].y) && (outCorners[1].x == outCorners[2].x)) {
// marker is aligned to image axes
Expand Down Expand Up @@ -150,6 +150,46 @@ void Board::setIds(InputArray ids_) {
ids_.copyTo(this->ids);
}

Ptr<Dictionary> Board::getDictionary() const {
return this->dictionary;
}

void Board::setDictionary(const Ptr<Dictionary> &_dictionary) {
this->dictionary = _dictionary;
}

const std::vector<std::vector<Point3f> >& Board::getObjPoints() const {
return this->objPoints;
}

void Board::setObjPoints(const vector<std::vector<Point3f>> &_objPoints) {
CV_Assert(!_objPoints.empty());
this->objPoints = _objPoints;
rightBottomBorder = _objPoints.front().front();
for (size_t i = 0; i < this->objPoints.size(); i++) {
for (int j = 0; j < 4; j++) {
const Point3f &corner = this->objPoints[i][j];
rightBottomBorder.x = std::max(rightBottomBorder.x, corner.x);
rightBottomBorder.y = std::max(rightBottomBorder.y, corner.y);
rightBottomBorder.z = std::max(rightBottomBorder.z, corner.z);
}
}
}

const Point3f& Board::getRightBottomBorder() const {
return this->rightBottomBorder;
}

const std::vector<int>& Board::getIds() const {
return this->ids;
}

void Board::changeId(int index, int newId) {
CV_Assert(index >= 0 && index < (int)ids.size());
CV_Assert(newId >= 0 && newId < dictionary->bytesList.rows);
this->ids[index] = newId;
}

Ptr<GridBoard> GridBoard::create(int markersX, int markersY, float markerLength, float markerSeparation,
const Ptr<Dictionary> &dictionary, int firstMarker) {
CV_Assert(markersX > 0 && markersY > 0 && markerLength > 0 && markerSeparation > 0);
Expand All @@ -158,11 +198,12 @@ Ptr<GridBoard> GridBoard::create(int markersX, int markersY, float markerLength,
res->gridImpl->sizeY = markersY;
res->gridImpl->markerLength = markerLength;
res->gridImpl->markerSeparation = markerSeparation;
res->dictionary = dictionary;
res->setDictionary(dictionary);

size_t totalMarkers = (size_t) markersX * markersY;
res->ids.resize(totalMarkers);
res->objPoints.reserve(totalMarkers);
std::vector<std::vector<Point3f> > objPoints;
objPoints.reserve(totalMarkers);

// fill ids with first identifiers
for (unsigned int i = 0; i < totalMarkers; i++) {
Expand All @@ -178,9 +219,10 @@ Ptr<GridBoard> GridBoard::create(int markersX, int markersY, float markerLength,
corners[1] = corners[0] + Point3f(markerLength, 0, 0);
corners[2] = corners[0] + Point3f(markerLength, markerLength, 0);
corners[3] = corners[0] + Point3f(0, markerLength, 0);
res->objPoints.push_back(corners);
objPoints.push_back(corners);
}
}
res->setObjPoints(objPoints);
res->rightBottomBorder = Point3f(markersX * markerLength + markerSeparation * (markersX - 1),
markersY * markerLength + markerSeparation * (markersY - 1), 0.f);
return res;
Expand Down Expand Up @@ -281,7 +323,7 @@ static inline void _getNearestMarkerCorners(CharucoBoard &board, float squareLen
board.nearestMarkerIdx.resize(board.chessboardCorners.size());
board.nearestMarkerCorners.resize(board.chessboardCorners.size());

unsigned int nMarkers = (unsigned int)board.ids.size();
unsigned int nMarkers = (unsigned int)board.getIds().size();
unsigned int nCharucoCorners = (unsigned int)board.chessboardCorners.size();
for(unsigned int i = 0; i < nCharucoCorners; i++) {
double minDist = -1; // distance of closest markers
Expand All @@ -290,7 +332,7 @@ static inline void _getNearestMarkerCorners(CharucoBoard &board, float squareLen
// calculate distance from marker center to charuco corner
Point3f center = Point3f(0, 0, 0);
for(unsigned int k = 0; k < 4; k++)
center += board.objPoints[j][k];
center += board.getObjPoints()[j][k];
center /= 4.;
double sqDistance;
Point3f distVector = charucoCorner - center;
Expand All @@ -313,7 +355,7 @@ static inline void _getNearestMarkerCorners(CharucoBoard &board, float squareLen
double minDistCorner = -1;
for(unsigned int k = 0; k < 4; k++) {
double sqDistance;
Point3f distVector = charucoCorner - board.objPoints[board.nearestMarkerIdx[i][j]][k];
Point3f distVector = charucoCorner - board.getObjPoints()[board.nearestMarkerIdx[i][j]][k];
sqDistance = distVector.x * distVector.x + distVector.y * distVector.y;
if(k == 0 || sqDistance < minDistCorner) {
// if this corner is closer to the charuco corner, assing its index
Expand All @@ -335,7 +377,8 @@ Ptr<CharucoBoard> CharucoBoard::create(int squaresX, int squaresY, float squareL
res->charucoImpl->sizeY = squaresY;
res->charucoImpl->squareLength = squareLength;
res->charucoImpl->markerLength = markerLength;
res->dictionary = dictionary;
res->setDictionary(dictionary);
std::vector<std::vector<Point3f> > objPoints;

float diffSquareMarkerLength = (squareLength - markerLength) / 2;
// calculate Board objPoints
Expand All @@ -350,12 +393,13 @@ Ptr<CharucoBoard> CharucoBoard::create(int squaresX, int squaresY, float squareL
corners[1] = corners[0] + Point3f(markerLength, 0, 0);
corners[2] = corners[0] + Point3f(markerLength, markerLength, 0);
corners[3] = corners[0] + Point3f(0, markerLength, 0);
res->objPoints.push_back(corners);
objPoints.push_back(corners);
// first ids in dictionary
int nextId = (int)res->ids.size();
res->ids.push_back(nextId);
}
}
res->setObjPoints(objPoints);

// now fill chessboardCorners
for(int y = 0; y < squaresY - 1; y++) {
Expand Down
Loading

0 comments on commit 230b6c9

Please sign in to comment.