@@ -12,39 +12,37 @@ namespace aruco {
12
12
// ! @addtogroup aruco
13
13
// ! @{
14
14
15
- /* * @brief
16
- * rvec/tvec define the right handed coordinate system of the marker.
15
+ /* * @brief rvec/tvec define the right handed coordinate system of the marker.
17
16
* PatternPos defines center this system and axes direction.
18
17
* Axis X (red color) - first coordinate, axis Y (green color) - second coordinate,
19
18
* axis Z (blue color) - third coordinate.
20
19
* @sa estimatePoseSingleMarkers(), @ref tutorial_aruco_detection
21
20
*/
22
21
enum PatternPos {
23
22
/* * @brief The marker coordinate system is centered on the middle of the marker.
24
- * The coordinates of the four corners (CCW order) of the marker in its own coordinate system are:
25
- * (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
26
- * (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0).
27
- *
28
- * These pattern points define this coordinate system:
29
- * 
30
- */
31
- CCW_center ,
23
+ * The coordinates of the four corners (CCW order) of the marker in its own coordinate system are:
24
+ * (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
25
+ * (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0).
26
+ *
27
+ * These pattern points define this coordinate system:
28
+ * 
29
+ */
30
+ CCW_CENTER ,
32
31
/* * @brief The marker coordinate system is centered on the top-left corner of the marker.
33
- * The coordinates of the four corners (CW order) of the marker in its own coordinate system are:
34
- * (0, 0, 0), (markerLength, 0, 0),
35
- * (markerLength, markerLength, 0), (0, markerLength, 0).
36
- *
37
- * These pattern points define this coordinate system:
38
- * 
39
- *
40
- * These pattern dots are convenient to use with a chessboard/ChArUco board.
41
- */
42
- CW_top_left_corner
32
+ * The coordinates of the four corners (CW order) of the marker in its own coordinate system are:
33
+ * (0, 0, 0), (markerLength, 0, 0),
34
+ * (markerLength, markerLength, 0), (0, markerLength, 0).
35
+ *
36
+ * These pattern points define this coordinate system:
37
+ * 
38
+ *
39
+ * These pattern dots are convenient to use with a chessboard/ChArUco board.
40
+ */
41
+ CW_TOP_LEFT_CORNER
43
42
};
44
43
45
- /* * @brief
46
- * Pose estimation parameters
47
- * @param pattern Defines center this system and axes direction (default PatternPos::CCW_center).
44
+ /* * @brief Pose estimation parameters
45
+ * @param pattern Defines center this system and axes direction (default PatternPos::CCW_CENTER).
48
46
* @param useExtrinsicGuess Parameter used for SOLVEPNP_ITERATIVE. If true (1), the function uses the provided
49
47
* rvec and tvec values as initial approximations of the rotation and translation vectors, respectively, and further
50
48
* optimizes them (default false).
@@ -56,7 +54,7 @@ struct CV_EXPORTS_W EstimateParameters {
56
54
CV_PROP_RW bool useExtrinsicGuess;
57
55
CV_PROP_RW SolvePnPMethod solvePnPMethod;
58
56
59
- EstimateParameters (): pattern(CCW_center ), useExtrinsicGuess(false ),
57
+ EstimateParameters (): pattern(CCW_CENTER ), useExtrinsicGuess(false ),
60
58
solvePnPMethod (SOLVEPNP_ITERATIVE) {}
61
59
62
60
CV_WRAP static Ptr<EstimateParameters> create () {
@@ -82,9 +80,9 @@ struct CV_EXPORTS_W EstimateParameters {
82
80
* Each element in rvecs corresponds to the specific marker in imgPoints.
83
81
* @param tvecs array of output translation vectors (e.g. std::vector<cv::Vec3d>).
84
82
* Each element in tvecs corresponds to the specific marker in imgPoints.
85
- * @param _objPoints array of object points of all the marker corners
83
+ * @param objPoints array of object points of all the marker corners
86
84
* @param estimateParameters set the origin of coordinate system and the coordinates of the four corners of the marker
87
- * (default estimateParameters.pattern = PatternPos::CCW_center , estimateParameters.useExtrinsicGuess = false,
85
+ * (default estimateParameters.pattern = PatternPos::CCW_CENTER , estimateParameters.useExtrinsicGuess = false,
88
86
* estimateParameters.solvePnPMethod = SOLVEPNP_ITERATIVE).
89
87
*
90
88
* This function receives the detected markers and returns their pose estimation respect to
@@ -103,8 +101,8 @@ struct CV_EXPORTS_W EstimateParameters {
103
101
*/
104
102
CV_EXPORTS_W void estimatePoseSingleMarkers (InputArrayOfArrays corners, float markerLength,
105
103
InputArray cameraMatrix, InputArray distCoeffs,
106
- OutputArray rvecs, OutputArray tvecs, OutputArray _objPoints = noArray(),
107
- Ptr<EstimateParameters> estimateParameters = EstimateParameters::create());
104
+ OutputArray rvecs, OutputArray tvecs, OutputArray objPoints = noArray(),
105
+ const Ptr<EstimateParameters>& estimateParameters = EstimateParameters::create());
108
106
109
107
/* *
110
108
* @brief Pose estimation for a board of markers
@@ -193,16 +191,18 @@ double calibrateCameraAruco(InputArrayOfArrays corners, InputArray ids, InputArr
193
191
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
194
192
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, OutputArray stdDeviationsIntrinsics,
195
193
OutputArray stdDeviationsExtrinsics, OutputArray perViewErrors, int flags = 0 ,
196
- TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30 , DBL_EPSILON));
194
+ const TermCriteria& criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30 , DBL_EPSILON));
197
195
198
- /* * @brief It's the same function as #calibrateCameraAruco but without calibration error estimation.
196
+ /* *
197
+ * @brief It's the same function as #calibrateCameraAruco but without calibration error estimation.
198
+ * @overload
199
199
*/
200
200
CV_EXPORTS_W double calibrateCameraAruco (InputArrayOfArrays corners, InputArray ids, InputArray counter,
201
201
const Ptr<Board> &board, Size imageSize, InputOutputArray cameraMatrix,
202
202
InputOutputArray distCoeffs, OutputArrayOfArrays rvecs = noArray(),
203
203
OutputArrayOfArrays tvecs = noArray(), int flags = 0,
204
- TermCriteria criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS,
205
- 30 , DBL_EPSILON));
204
+ const TermCriteria& criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS,
205
+ 30 , DBL_EPSILON));
206
206
207
207
/* *
208
208
* @brief Pose estimation for a ChArUco board given some of their corners
@@ -267,17 +267,18 @@ double calibrateCameraCharuco(InputArrayOfArrays charucoCorners, InputArrayOfArr
267
267
const Ptr<CharucoBoard> &board, Size imageSize, InputOutputArray cameraMatrix,
268
268
InputOutputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
269
269
OutputArray stdDeviationsIntrinsics, OutputArray stdDeviationsExtrinsics,
270
- OutputArray perViewErrors, int flags = 0 , TermCriteria criteria = TermCriteria(
270
+ OutputArray perViewErrors, int flags = 0 , const TermCriteria& criteria = TermCriteria(
271
271
TermCriteria::COUNT + TermCriteria::EPS, 30 , DBL_EPSILON));
272
272
273
- /* * @brief It's the same function as #calibrateCameraCharuco but without calibration error estimation.
274
- */
273
+ /* *
274
+ * @brief It's the same function as #calibrateCameraCharuco but without calibration error estimation.
275
+ */
275
276
CV_EXPORTS_W double calibrateCameraCharuco (InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds,
276
277
const Ptr<CharucoBoard> &board, Size imageSize,
277
278
InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
278
279
OutputArrayOfArrays rvecs = noArray(),
279
280
OutputArrayOfArrays tvecs = noArray(), int flags = 0,
280
- TermCriteria criteria=TermCriteria(TermCriteria::COUNT +
281
+ const TermCriteria& criteria=TermCriteria(TermCriteria::COUNT +
281
282
TermCriteria::EPS, 30 , DBL_EPSILON));
282
283
// ! @}
283
284
0 commit comments