Skip to content

Commit 7ce8a88

Browse files
author
AleksandrPanov
committed
update docs, add singlemarkersaxes2.jpg
1 parent e4c264a commit 7ce8a88

File tree

3 files changed

+22
-5
lines changed

3 files changed

+22
-5
lines changed

modules/aruco/include/opencv2/aruco.hpp

Lines changed: 20 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -226,24 +226,38 @@ CV_EXPORTS_W void detectMarkers(InputArray image, const Ptr<Dictionary> &diction
226226
* Axis X (red color) - first coordinate
227227
* Axis Y (green color) - second coordinate
228228
* Axis Z (blue color) - third coordinate
229+
* @sa estimatePoseSingleMarkers(), @ref tutorial_aruco_detection
229230
*/
230231
enum PatternPos {
231232
/** @brief The marker coordinate system is centered on the middle of the marker.
232-
* The coordinates of the four corners of the marker in its own coordinate system are:
233+
* The coordinates of the four corners (CCW order) of the marker in its own coordinate system are:
233234
* (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
234-
* (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0)
235+
* (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0).
236+
*
235237
* These pattern points define this coordinate system:
238+
* ![Image with axes drawn](images/singlemarkersaxes.jpg)
236239
*/
237240
CCW_center,
238241
/** @brief The marker coordinate system is centered on the top-left corner of the marker.
239-
* The coordinates of the four corners of the marker in its own coordinate system are:
242+
* The coordinates of the four corners (CW order) of the marker in its own coordinate system are:
240243
* (0, 0, 0), (markerLength, 0, 0),
241-
* (markerLength, markerLength, 0), (0, markerLength, 0)
244+
* (markerLength, markerLength, 0), (0, markerLength, 0).
245+
*
242246
* These pattern points define this coordinate system:
247+
* ![Image with axes drawn](images/singlemarkersaxes2.jpg)
243248
*/
244249
CW_top_left_corner
245250
};
246251

252+
/** @brief
253+
* Pose estimation parameters
254+
* @param pattern Defines center this system and axes direction.
255+
* @param useExtrinsicGuess Parameter used for SOLVEPNP_ITERATIVE. If true (1), the function uses the provided
256+
* rvec and tvec values as initial approximations of the rotation and translation vectors, respectively, and further
257+
* optimizes them.
258+
* @param solvePnPMethod Method for solving a PnP problem: see @ref calib3d_solvePnP_flags.
259+
* @sa PatternPos, solvePnP(), @ref tutorial_aruco_detection
260+
*/
247261
struct CV_EXPORTS_W EstimateParameters {
248262
CV_PROP_RW PatternPos pattern;
249263
CV_PROP_RW bool useExtrinsicGuess;
@@ -289,6 +303,8 @@ struct CV_EXPORTS_W EstimateParameters {
289303
* (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
290304
* (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0)
291305
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
306+
* @sa PatternPos
307+
* @sa @ref tutorial_aruco_detection
292308
*/
293309
CV_EXPORTS_W void estimatePoseSingleMarkers(InputArrayOfArrays corners, float markerLength,
294310
InputArray cameraMatrix, InputArray distCoeffs,

modules/aruco/src/aruco.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -810,7 +810,8 @@ static void _identifyCandidates(InputArray _image, vector< vector< vector< Point
810810

811811

812812
/**
813-
* @brief Return object points for the system centered in a top left corner of single marker, given the marker length
813+
* @brief Return object points for the system centered in a middle (by default) or in a top left corner of single
814+
* marker, given the marker length
814815
*/
815816
static void _getSingleMarkerObjectPoints(float markerLength, OutputArray _objPoints,
816817
EstimateParameters estimateParameters) {
Loading

0 commit comments

Comments
 (0)