Skip to content

Commit f8470c6

Browse files
add axes test, remove drawAxis(), update tutorial
1 parent c8936ad commit f8470c6

27 files changed

+100
-102
lines changed

modules/aruco/include/opencv2/aruco.hpp

Lines changed: 5 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -250,8 +250,9 @@ CV_EXPORTS_W void detectMarkers(InputArray image, const Ptr<Dictionary> &diction
250250
* The marker corrdinate system is centered on the middle of the marker, with the Z axis
251251
* perpendicular to the marker plane.
252252
* The coordinates of the four corners of the marker in its own coordinate system are:
253-
* (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
254-
* (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0)
253+
* (0, 0, 0), (markerLength, 0, 0),
254+
* (markerLength, markerLength, 0), (0, markerLength, 0)
255+
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
255256
*/
256257
CV_EXPORTS_W void estimatePoseSingleMarkers(InputArrayOfArrays corners, float markerLength,
257258
InputArray cameraMatrix, InputArray distCoeffs,
@@ -412,6 +413,7 @@ class CV_EXPORTS_W GridBoard : public Board {
412413
* Input markers that are not included in the board layout are ignored.
413414
* The function returns the number of markers from the input employed for the board pose estimation.
414415
* Note that returning a 0 means the pose has not been estimated.
416+
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
415417
*/
416418
CV_EXPORTS_W int estimatePoseBoard(InputArrayOfArrays corners, InputArray ids, const Ptr<Board> &board,
417419
InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec,
@@ -476,36 +478,14 @@ CV_EXPORTS_W void refineDetectedMarkers(
476478
* Given an array of detected marker corners and its corresponding ids, this functions draws
477479
* the markers in the image. The marker borders are painted and the markers identifiers if provided.
478480
* Useful for debugging purposes.
481+
*
479482
*/
480483
CV_EXPORTS_W void drawDetectedMarkers(InputOutputArray image, InputArrayOfArrays corners,
481484
InputArray ids = noArray(),
482485
Scalar borderColor = Scalar(0, 255, 0));
483486

484487

485488

486-
/**
487-
* @brief Draw coordinate system axis from pose estimation
488-
*
489-
* @param image input/output image. It must have 1 or 3 channels. The number of channels is not
490-
* altered.
491-
* @param cameraMatrix input 3x3 floating-point camera matrix
492-
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
493-
* @param distCoeffs vector of distortion coefficients
494-
* \f$(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6],[s_1, s_2, s_3, s_4]])\f$ of 4, 5, 8 or 12 elements
495-
* @param rvec rotation vector of the coordinate system that will be drawn. (@sa Rodrigues).
496-
* @param tvec translation vector of the coordinate system that will be drawn.
497-
* @param length length of the painted axis in the same unit than tvec (usually in meters)
498-
*
499-
* Given the pose estimation of a marker or board, this function draws the axis of the world
500-
* coordinate system, i.e. the system centered on the marker/board. Useful for debugging purposes.
501-
*
502-
* @deprecated use cv::drawFrameAxes
503-
*/
504-
CV_EXPORTS_W void drawAxis(InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs,
505-
InputArray rvec, InputArray tvec, float length, int thickness=3);
506-
507-
508-
509489
/**
510490
* @brief Draw a canonical marker image
511491
*

modules/aruco/include/opencv2/aruco/charuco.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -181,6 +181,7 @@ CV_EXPORTS_W int interpolateCornersCharuco(InputArrayOfArrays markerCorners, Inp
181181
* This function estimates a Charuco board pose from some detected corners.
182182
* The function checks if the input corners are enough and valid to perform pose estimation.
183183
* If pose estimation is valid, returns true, else returns false.
184+
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
184185
*/
185186
CV_EXPORTS_W bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray charucoIds,
186187
const Ptr<CharucoBoard> &board, InputArray cameraMatrix,
@@ -275,6 +276,7 @@ CV_EXPORTS_W double calibrateCameraCharuco(
275276
* diamond.
276277
* @param cameraMatrix Optional camera calibration matrix.
277278
* @param distCoeffs Optional camera distortion coefficients.
279+
* @param dictionary dictionary of markers indicating the type of markers.
278280
*
279281
* This function detects Diamond markers from the previous detected ArUco markers. The diamonds
280282
* are returned in the diamondCorners and diamondIds parameters. If camera calibration parameters
@@ -286,7 +288,7 @@ CV_EXPORTS_W void detectCharucoDiamond(InputArray image, InputArrayOfArrays mark
286288
OutputArrayOfArrays diamondCorners, OutputArray diamondIds,
287289
InputArray cameraMatrix = noArray(),
288290
InputArray distCoeffs = noArray(),
289-
Ptr<Dictionary> dict = getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME(0)));
291+
Ptr<Dictionary> dictionary = getPredefinedDictionary(PREDEFINED_DICTIONARY_NAME(0)));
290292

291293

292294

modules/aruco/samples/calibrate_camera.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ int main(int argc, char *argv[]) {
101101
if(parser.get<bool>("zt")) calibrationFlags |= CALIB_ZERO_TANGENT_DIST;
102102
if(parser.get<bool>("pc")) calibrationFlags |= CALIB_FIX_PRINCIPAL_POINT;
103103

104-
Ptr<aruco::DetectorParameters> detectorParams;
104+
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
105105
if(parser.has("dp")) {
106106
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
107107
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);

modules/aruco/samples/calibrate_camera_charuco.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,7 +102,7 @@ int main(int argc, char *argv[]) {
102102
if(parser.get<bool>("zt")) calibrationFlags |= CALIB_ZERO_TANGENT_DIST;
103103
if(parser.get<bool>("pc")) calibrationFlags |= CALIB_FIX_PRINCIPAL_POINT;
104104

105-
Ptr<aruco::DetectorParameters> detectorParams;
105+
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
106106
if(parser.has("dp")) {
107107
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
108108
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);

modules/aruco/samples/detect_board.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ int main(int argc, char *argv[]) {
9797
}
9898
}
9999

100-
Ptr<aruco::DetectorParameters> detectorParams;
100+
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
101101
if(parser.has("dp")) {
102102
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
103103
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);
@@ -199,7 +199,7 @@ int main(int argc, char *argv[]) {
199199
aruco::drawDetectedMarkers(imageCopy, rejected, noArray(), Scalar(100, 0, 255));
200200

201201
if(markersOfBoardDetected > 0)
202-
aruco::drawAxis(imageCopy, camMatrix, distCoeffs, rvec, tvec, axisLength);
202+
cv::drawFrameAxes(imageCopy, camMatrix, distCoeffs, rvec, tvec, axisLength);
203203

204204
imshow("out", imageCopy);
205205
char key = (char)waitKey(waitTime);

modules/aruco/samples/detect_board_charuco.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ int main(int argc, char *argv[]) {
9999
}
100100
}
101101

102-
Ptr<aruco::DetectorParameters> detectorParams;
102+
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
103103
if(parser.has("dp")) {
104104
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
105105
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);
@@ -213,7 +213,7 @@ int main(int argc, char *argv[]) {
213213
}
214214

215215
if(validPose)
216-
aruco::drawAxis(imageCopy, camMatrix, distCoeffs, rvec, tvec, axisLength);
216+
cv::drawFrameAxes(imageCopy, camMatrix, distCoeffs, rvec, tvec, axisLength);
217217

218218
imshow("out", imageCopy);
219219
char key = (char)waitKey(waitTime);

modules/aruco/samples/detect_diamonds.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ int main(int argc, char *argv[]) {
8787
bool autoScale = parser.has("as");
8888
float autoScaleFactor = autoScale ? parser.get<float>("as") : 1.f;
8989

90-
Ptr<aruco::DetectorParameters> detectorParams;
90+
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
9191
if(parser.has("dp")) {
9292
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
9393
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);
@@ -219,8 +219,8 @@ int main(int argc, char *argv[]) {
219219

220220
if(estimatePose) {
221221
for(unsigned int i = 0; i < diamondIds.size(); i++)
222-
aruco::drawAxis(imageCopy, camMatrix, distCoeffs, rvecs[i], tvecs[i],
223-
squareLength * 0.5f);
222+
cv::drawFrameAxes(imageCopy, camMatrix, distCoeffs, rvecs[i], tvecs[i],
223+
squareLength * 1.1f);
224224
}
225225
}
226226

modules/aruco/samples/detect_markers.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ int main(int argc, char *argv[]) {
8080
bool estimatePose = parser.has("c");
8181
float markerLength = parser.get<float>("l");
8282

83-
Ptr<aruco::DetectorParameters> detectorParams;
83+
Ptr<aruco::DetectorParameters> detectorParams = aruco::DetectorParameters::create();
8484
if(parser.has("dp")) {
8585
FileStorage fs(parser.get<string>("dp"), FileStorage::READ);
8686
bool readOk = aruco::DetectorParameters::readDetectorParameters(fs.root(), detectorParams);
@@ -179,8 +179,7 @@ int main(int argc, char *argv[]) {
179179

180180
if(estimatePose) {
181181
for(unsigned int i = 0; i < ids.size(); i++)
182-
aruco::drawAxis(imageCopy, camMatrix, distCoeffs, rvecs[i], tvecs[i],
183-
markerLength * 0.5f);
182+
cv::drawFrameAxes(imageCopy, camMatrix, distCoeffs, rvecs[i], tvecs[i], markerLength * 1.5f, 2);
184183
}
185184
}
186185

modules/aruco/samples/tutorial_charuco_create_detect.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ static inline void detectCharucoBoardWithCalibrationPose()
7272
//! [pose]
7373
// if charuco pose is valid
7474
if (valid)
75-
cv::aruco::drawAxis(imageCopy, cameraMatrix, distCoeffs, rvec, tvec, 0.1f);
75+
cv::drawFrameAxes(imageCopy, cameraMatrix, distCoeffs, rvec, tvec, 0.1f);
7676
}
7777
}
7878
cv::imshow("out", imageCopy);

modules/aruco/src/aruco.cpp

Lines changed: 5 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -811,11 +811,11 @@ static void _getSingleMarkerObjectPoints(float markerLength, OutputArray _objPoi
811811

812812
_objPoints.create(4, 1, CV_32FC3);
813813
Mat objPoints = _objPoints.getMat();
814-
// set coordinate system in the middle of the marker, with Z pointing out
815-
objPoints.ptr< Vec3f >(0)[0] = Vec3f(-markerLength / 2.f, markerLength / 2.f, 0);
816-
objPoints.ptr< Vec3f >(0)[1] = Vec3f(markerLength / 2.f, markerLength / 2.f, 0);
817-
objPoints.ptr< Vec3f >(0)[2] = Vec3f(markerLength / 2.f, -markerLength / 2.f, 0);
818-
objPoints.ptr< Vec3f >(0)[3] = Vec3f(-markerLength / 2.f, -markerLength / 2.f, 0);
814+
// set coordinate system in the top-left corner of the marker, with Z pointing out
815+
objPoints.ptr< Vec3f >(0)[0] = Vec3f(0.f, 0.f, 0);
816+
objPoints.ptr< Vec3f >(0)[1] = Vec3f(markerLength, 0.f, 0);
817+
objPoints.ptr< Vec3f >(0)[2] = Vec3f(markerLength, markerLength, 0);
818+
objPoints.ptr< Vec3f >(0)[3] = Vec3f(0.f, markerLength, 0);
819819
}
820820

821821

@@ -1783,24 +1783,6 @@ void drawDetectedMarkers(InputOutputArray _image, InputArrayOfArrays _corners,
17831783
}
17841784

17851785

1786-
1787-
/**
1788-
*/
1789-
void drawAxis(InputOutputArray _image, InputArray _cameraMatrix, InputArray _distCoeffs, InputArray _rvec,
1790-
InputArray _tvec, float length, int thickness)
1791-
{
1792-
vector<Point3f> axis;
1793-
axis.push_back(Point3f(0.f, 0.f, 0.f));
1794-
axis.push_back(Point3f(length, 0.f, 0.f));
1795-
axis.push_back(Point3f(0.f, length, 0.f));
1796-
axis.push_back(Point3f(0.f, 0.f, -length));
1797-
vector<Point2f> axis_to_img;
1798-
projectPoints(axis, _rvec, _tvec, _cameraMatrix, _distCoeffs, axis_to_img);
1799-
line(_image, Point2i(axis_to_img[0]), Point2i(axis_to_img[1]), Scalar(255,0,0), thickness);
1800-
line(_image, Point2i(axis_to_img[0]), Point2i(axis_to_img[2]), Scalar(0,255,0), thickness);
1801-
line(_image, Point2i(axis_to_img[0]), Point2i(axis_to_img[3]), Scalar(0,0,255), thickness);
1802-
}
1803-
18041786
/**
18051787
*/
18061788
void drawMarker(const Ptr<Dictionary> &dictionary, int id, int sidePixels, OutputArray _img, int borderBits) {

0 commit comments

Comments
 (0)