增加aruco代码

This commit is contained in:
Motorman 2025-08-26 23:03:14 +08:00
parent 02b0cc14c1
commit 811253ab20
9 changed files with 723 additions and 0 deletions

View File

@ -148,6 +148,9 @@
<ClCompile Include="camCalib.cpp" />
<ClCompile Include="lineDetection_steger.cpp" />
<ClCompile Include="onnxDetector.cpp" />
<ClCompile Include="sourceCode\aruco\aruco.cpp" />
<ClCompile Include="sourceCode\aruco\aruco_calib.cpp" />
<ClCompile Include="sourceCode\aruco\charuco.cpp" />
<ClCompile Include="sourceCode\FitMapParam.cpp" />
<ClCompile Include="sourceCode\MonoLaserCalibrate.cpp" />
</ItemGroup>

View File

@ -13,6 +13,9 @@
<UniqueIdentifier>{67DA6AB6-F800-4c08-8B7A-83BB121AAD01}</UniqueIdentifier>
<Extensions>rc;ico;cur;bmp;dlg;rc2;rct;bin;rgs;gif;jpg;jpeg;jpe;resx;tiff;tif;png;wav;mfcribbon-ms</Extensions>
</Filter>
<Filter Include="源文件\aruco">
<UniqueIdentifier>{5709fb07-01a0-47f3-b3c7-11842aaaa85e}</UniqueIdentifier>
</Filter>
</ItemGroup>
<ItemGroup>
<ClCompile Include="camCalib.cpp">
@ -30,6 +33,15 @@
<ClCompile Include="onnxDetector.cpp">
<Filter>源文件</Filter>
</ClCompile>
<ClCompile Include="sourceCode\aruco\aruco.cpp">
<Filter>源文件\aruco</Filter>
</ClCompile>
<ClCompile Include="sourceCode\aruco\aruco_calib.cpp">
<Filter>源文件\aruco</Filter>
</ClCompile>
<ClCompile Include="sourceCode\aruco\charuco.cpp">
<Filter>源文件\aruco</Filter>
</ClCompile>
</ItemGroup>
<ItemGroup>
<ClInclude Include="sourceCode\MonoLaserCalibrate.h">

View File

@ -0,0 +1,103 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef OPENCV_ARUCO_HPP
#define OPENCV_ARUCO_HPP
#include "opencv2/objdetect/aruco_detector.hpp"
#include "aruco/aruco_calib.hpp"
namespace cv {
namespace aruco {
/**
* @defgroup aruco Aruco markers, module functionality was moved to objdetect module
* @{
* ArUco Marker Detection, module functionality was moved to objdetect module
* @sa ArucoDetector, CharucoDetector, Board, GridBoard, CharucoBoard
* @}
*/
//! @addtogroup aruco
//! @{
/** @brief detect markers
@deprecated Use class ArucoDetector::detectMarkers
*/
CV_EXPORTS_W void detectMarkers(InputArray image, const Ptr<Dictionary> &dictionary, OutputArrayOfArrays corners,
OutputArray ids, const Ptr<DetectorParameters> &parameters = makePtr<DetectorParameters>(),
OutputArrayOfArrays rejectedImgPoints = noArray());
/** @brief refine detected markers
@deprecated Use class ArucoDetector::refineDetectedMarkers
*/
CV_EXPORTS_W void refineDetectedMarkers(InputArray image,const Ptr<Board> &board,
InputOutputArrayOfArrays detectedCorners,
InputOutputArray detectedIds, InputOutputArrayOfArrays rejectedCorners,
InputArray cameraMatrix = noArray(), InputArray distCoeffs = noArray(),
float minRepDistance = 10.f, float errorCorrectionRate = 3.f,
bool checkAllOrders = true, OutputArray recoveredIdxs = noArray(),
const Ptr<DetectorParameters> &parameters = makePtr<DetectorParameters>());
/** @brief draw planar board
@deprecated Use Board::generateImage
*/
CV_EXPORTS_W void drawPlanarBoard(const Ptr<Board> &board, Size outSize, OutputArray img, int marginSize,
int borderBits);
/** @brief get board object and image points
@deprecated Use Board::matchImagePoints
*/
CV_EXPORTS_W void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners,
InputArray detectedIds, OutputArray objPoints, OutputArray imgPoints);
/** @deprecated Use Board::matchImagePoints and cv::solvePnP
*/
CV_EXPORTS_W int estimatePoseBoard(InputArrayOfArrays corners, InputArray ids, const Ptr<Board> &board,
InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess = false);
/**
* @brief Pose estimation for a ChArUco board given some of their corners
* @param charucoCorners vector of detected charuco corners
* @param charucoIds list of identifiers for each corner in charucoCorners
* @param board layout of ChArUco board.
* @param cameraMatrix input 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs vector of distortion coefficients
* \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
* @param rvec Output vector (e.g. cv::Mat) corresponding to the rotation vector of the board
* (see cv::Rodrigues).
* @param tvec Output vector (e.g. cv::Mat) corresponding to the translation vector of the board.
* @param useExtrinsicGuess defines whether initial guess for \b rvec and \b tvec will be used or not.
*
* This function estimates a Charuco board pose from some detected corners.
* 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.
* @deprecated Use CharucoBoard::matchImagePoints and cv::solvePnP
* @sa use cv::drawFrameAxes to get world coordinate system axis for object points
*/
CV_EXPORTS_W bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray charucoIds,
const Ptr<CharucoBoard> &board, InputArray cameraMatrix,
InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess = false);
/** @deprecated Use cv::solvePnP
*/
CV_EXPORTS_W void estimatePoseSingleMarkers(InputArrayOfArrays corners, float markerLength,
InputArray cameraMatrix, InputArray distCoeffs,
OutputArray rvecs, OutputArray tvecs, OutputArray objPoints = noArray(),
const Ptr<EstimateParameters>& estimateParameters = makePtr<EstimateParameters>());
/** @deprecated Use CharucoBoard::checkCharucoCornersCollinear
*/
CV_EXPORTS_W bool testCharucoCornersCollinear(const Ptr<CharucoBoard> &board, InputArray charucoIds);
//! @}
}
}
#endif

View File

@ -0,0 +1,143 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "precomp.hpp"
#include "../aruco.hpp"
#include <opencv2/calib3d.hpp>
#include <opencv2/core/utils/logger.hpp>
namespace cv {
namespace aruco {
using namespace std;
void detectMarkers(InputArray _image, const Ptr<Dictionary> &_dictionary, OutputArrayOfArrays _corners,
OutputArray _ids, const Ptr<DetectorParameters> &_params,
OutputArrayOfArrays _rejectedImgPoints) {
ArucoDetector detector(*_dictionary, *_params);
detector.detectMarkers(_image, _corners, _ids, _rejectedImgPoints);
}
void refineDetectedMarkers(InputArray _image, const Ptr<Board> &_board,
InputOutputArrayOfArrays _detectedCorners, InputOutputArray _detectedIds,
InputOutputArrayOfArrays _rejectedCorners, InputArray _cameraMatrix,
InputArray _distCoeffs, float minRepDistance, float errorCorrectionRate,
bool checkAllOrders, OutputArray _recoveredIdxs,
const Ptr<DetectorParameters> &_params) {
RefineParameters refineParams(minRepDistance, errorCorrectionRate, checkAllOrders);
ArucoDetector detector(_board->getDictionary(), *_params, refineParams);
detector.refineDetectedMarkers(_image, *_board, _detectedCorners, _detectedIds, _rejectedCorners, _cameraMatrix,
_distCoeffs, _recoveredIdxs);
}
void drawPlanarBoard(const Ptr<Board> &board, Size outSize, const _OutputArray &img, int marginSize, int borderBits) {
board->generateImage(outSize, img, marginSize, borderBits);
}
void getBoardObjectAndImagePoints(const Ptr<Board> &board, InputArrayOfArrays detectedCorners, InputArray detectedIds,
OutputArray objPoints, OutputArray imgPoints) {
board->matchImagePoints(detectedCorners, detectedIds, objPoints, imgPoints);
}
int estimatePoseBoard(InputArrayOfArrays corners, InputArray ids, const Ptr<Board> &board,
InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess) {
CV_Assert(corners.total() == ids.total());
// get object and image points for the solvePnP function
Mat objPoints, imgPoints;
board->matchImagePoints(corners, ids, objPoints, imgPoints);
CV_Assert(imgPoints.total() == objPoints.total());
if(objPoints.total() == 0) // 0 of the detected markers in board
return 0;
solvePnP(objPoints, imgPoints, cameraMatrix, distCoeffs, rvec, tvec, useExtrinsicGuess);
// divide by four since all the four corners are concatenated in the array for each marker
return (int)objPoints.total() / 4;
}
bool estimatePoseCharucoBoard(InputArray charucoCorners, InputArray charucoIds,
const Ptr<CharucoBoard> &board, InputArray cameraMatrix,
InputArray distCoeffs, InputOutputArray rvec,
InputOutputArray tvec, bool useExtrinsicGuess) {
CV_Assert((charucoCorners.getMat().total() == charucoIds.getMat().total()));
if(charucoIds.getMat().total() < 4) return false;
// get object and image points for the solvePnP function
Mat objPoints, imgPoints;
board->matchImagePoints(charucoCorners, charucoIds, objPoints, imgPoints);
try {
solvePnP(objPoints, imgPoints, cameraMatrix, distCoeffs, rvec, tvec, useExtrinsicGuess);
}
catch (const cv::Exception& e) {
CV_LOG_WARNING(NULL, "estimatePoseCharucoBoard: " << std::endl << e.what());
return false;
}
return objPoints.total() > 0ull;
}
bool testCharucoCornersCollinear(const Ptr<CharucoBoard> &board, InputArray charucoIds) {
return board->checkCharucoCornersCollinear(charucoIds);
}
/**
* @brief Return object points for the system centered in a middle (by default) or in a top left corner of single
* marker, given the marker length
*/
static Mat _getSingleMarkerObjectPoints(float markerLength, const EstimateParameters& estimateParameters) {
CV_Assert(markerLength > 0);
Mat objPoints(4, 1, CV_32FC3);
// set coordinate system in the top-left corner of the marker, with Z pointing out
if (estimateParameters.pattern == ARUCO_CW_TOP_LEFT_CORNER) {
objPoints.ptr<Vec3f>(0)[0] = Vec3f(0.f, 0.f, 0);
objPoints.ptr<Vec3f>(0)[1] = Vec3f(markerLength, 0.f, 0);
objPoints.ptr<Vec3f>(0)[2] = Vec3f(markerLength, markerLength, 0);
objPoints.ptr<Vec3f>(0)[3] = Vec3f(0.f, markerLength, 0);
}
else if (estimateParameters.pattern == ARUCO_CCW_CENTER) {
objPoints.ptr<Vec3f>(0)[0] = Vec3f(-markerLength/2.f, markerLength/2.f, 0);
objPoints.ptr<Vec3f>(0)[1] = Vec3f(markerLength/2.f, markerLength/2.f, 0);
objPoints.ptr<Vec3f>(0)[2] = Vec3f(markerLength/2.f, -markerLength/2.f, 0);
objPoints.ptr<Vec3f>(0)[3] = Vec3f(-markerLength/2.f, -markerLength/2.f, 0);
}
else
CV_Error(Error::StsBadArg, "Unknown estimateParameters pattern");
return objPoints;
}
void estimatePoseSingleMarkers(InputArrayOfArrays _corners, float markerLength,
InputArray _cameraMatrix, InputArray _distCoeffs,
OutputArray _rvecs, OutputArray _tvecs, OutputArray _objPoints,
const Ptr<EstimateParameters>& estimateParameters) {
CV_Assert(markerLength > 0);
Mat markerObjPoints = _getSingleMarkerObjectPoints(markerLength, *estimateParameters);
int nMarkers = (int)_corners.total();
_rvecs.create(nMarkers, 1, CV_64FC3);
_tvecs.create(nMarkers, 1, CV_64FC3);
Mat rvecs = _rvecs.getMat(), tvecs = _tvecs.getMat();
//// for each marker, calculate its pose
parallel_for_(Range(0, nMarkers), [&](const Range& range) {
const int begin = range.start;
const int end = range.end;
for (int i = begin; i < end; i++) {
solvePnP(markerObjPoints, _corners.getMat(i), _cameraMatrix, _distCoeffs, rvecs.at<Vec3d>(i),
tvecs.at<Vec3d>(i), estimateParameters->useExtrinsicGuess, estimateParameters->solvePnPMethod);
}
});
if(_objPoints.needed()){
markerObjPoints.convertTo(_objPoints, -1);
}
}
}
}

View File

@ -0,0 +1,99 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "aruco_calib.hpp"
#include <opencv2/calib3d.hpp>
namespace cv {
namespace aruco {
using namespace std;
using namespace cv;
EstimateParameters::EstimateParameters() : pattern(ARUCO_CCW_CENTER), useExtrinsicGuess(false),
solvePnPMethod(SOLVEPNP_ITERATIVE) {}
double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter,
const Ptr<Board> &board, Size imageSize, InputOutputArray _cameraMatrix,
InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs,
OutputArrayOfArrays _tvecs,
OutputArray _stdDeviationsIntrinsics,
OutputArray _stdDeviationsExtrinsics,
OutputArray _perViewErrors,
int flags, const TermCriteria& criteria) {
// for each frame, get properly processed imagePoints and objectPoints for the calibrateCamera
// function
vector<Mat> processedObjectPoints, processedImagePoints;
size_t nFrames = _counter.total();
int markerCounter = 0;
for(size_t frame = 0; frame < nFrames; frame++) {
int nMarkersInThisFrame = _counter.getMat().ptr< int >()[frame];
vector<Mat> thisFrameCorners;
vector<int> thisFrameIds;
CV_Assert(nMarkersInThisFrame > 0);
thisFrameCorners.reserve((size_t) nMarkersInThisFrame);
thisFrameIds.reserve((size_t) nMarkersInThisFrame);
for(int j = markerCounter; j < markerCounter + nMarkersInThisFrame; j++) {
thisFrameCorners.push_back(_corners.getMat(j));
thisFrameIds.push_back(_ids.getMat().ptr< int >()[j]);
}
markerCounter += nMarkersInThisFrame;
Mat currentImgPoints, currentObjPoints;
board->matchImagePoints(thisFrameCorners, thisFrameIds, currentObjPoints,
currentImgPoints);
if(currentImgPoints.total() > 0 && currentObjPoints.total() > 0) {
processedImagePoints.push_back(currentImgPoints);
processedObjectPoints.push_back(currentObjPoints);
}
}
return calibrateCamera(processedObjectPoints, processedImagePoints, imageSize, _cameraMatrix, _distCoeffs, _rvecs,
_tvecs, _stdDeviationsIntrinsics, _stdDeviationsExtrinsics, _perViewErrors, flags, criteria);
}
double calibrateCameraAruco(InputArrayOfArrays _corners, InputArray _ids, InputArray _counter, const Ptr<Board> &board,
Size imageSize, InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs,
OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs, int flags, const TermCriteria& criteria) {
return calibrateCameraAruco(_corners, _ids, _counter, board, imageSize, _cameraMatrix, _distCoeffs,
_rvecs, _tvecs, noArray(), noArray(), noArray(), flags, criteria);
}
double calibrateCameraCharuco(InputArrayOfArrays _charucoCorners, InputArrayOfArrays _charucoIds,
const Ptr<CharucoBoard> &_board, Size imageSize,
InputOutputArray _cameraMatrix, InputOutputArray _distCoeffs,
OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs,
OutputArray _stdDeviationsIntrinsics,
OutputArray _stdDeviationsExtrinsics,
OutputArray _perViewErrors,
int flags, const TermCriteria& criteria) {
CV_Assert(_charucoIds.total() > 0 && (_charucoIds.total() == _charucoCorners.total()));
// Join object points of charuco corners in a single vector for calibrateCamera() function
vector<vector<Point3f> > allObjPoints;
allObjPoints.resize(_charucoIds.total());
for(unsigned int i = 0; i < _charucoIds.total(); i++) {
unsigned int nCorners = (unsigned int)_charucoIds.getMat(i).total();
CV_Assert(nCorners > 0 && nCorners == _charucoCorners.getMat(i).total());
allObjPoints[i].reserve(nCorners);
for(unsigned int j = 0; j < nCorners; j++) {
int pointId = _charucoIds.getMat(i).at< int >(j);
CV_Assert(pointId >= 0 && pointId < (int)_board->getChessboardCorners().size());
allObjPoints[i].push_back(_board->getChessboardCorners()[pointId]);
}
}
return calibrateCamera(allObjPoints, _charucoCorners, imageSize, _cameraMatrix, _distCoeffs, _rvecs, _tvecs,
_stdDeviationsIntrinsics, _stdDeviationsExtrinsics, _perViewErrors, flags, criteria);
}
double calibrateCameraCharuco(InputArrayOfArrays _charucoCorners, InputArrayOfArrays _charucoIds,
const Ptr<CharucoBoard> &_board, Size imageSize, InputOutputArray _cameraMatrix,
InputOutputArray _distCoeffs, OutputArrayOfArrays _rvecs, OutputArrayOfArrays _tvecs,
int flags, const TermCriteria& criteria) {
return calibrateCameraCharuco(_charucoCorners, _charucoIds, _board, imageSize, _cameraMatrix, _distCoeffs, _rvecs,
_tvecs, noArray(), noArray(), noArray(), flags, criteria);
}
}
}

View File

@ -0,0 +1,180 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef OPENCV_ARUCO_CALIB_POSE_HPP
#define OPENCV_ARUCO_CALIB_POSE_HPP
#include <opencv2/objdetect/aruco_board.hpp>
namespace cv {
namespace aruco {
//! @addtogroup aruco
//! @{
/** @brief rvec/tvec define the right handed coordinate system of the marker.
*
* PatternPositionType defines center this system and axes direction.
* Axis X (red color) - first coordinate, axis Y (green color) - second coordinate,
* axis Z (blue color) - third coordinate.
*
* @deprecated Use Board::matchImagePoints and cv::solvePnP
*
* @sa estimatePoseSingleMarkers()
*/
enum PatternPositionType {
/** @brief The marker coordinate system is centered on the middle of the marker.
*
* The coordinates of the four corners (CCW order) of the marker in its own coordinate system are:
* (-markerLength/2, markerLength/2, 0), (markerLength/2, markerLength/2, 0),
* (markerLength/2, -markerLength/2, 0), (-markerLength/2, -markerLength/2, 0).
*/
ARUCO_CCW_CENTER,
/** @brief The marker coordinate system is centered on the top-left corner of the marker.
*
* The coordinates of the four corners (CW order) of the marker in its own coordinate system are:
* (0, 0, 0), (markerLength, 0, 0),
* (markerLength, markerLength, 0), (0, markerLength, 0).
*
* These pattern dots are convenient to use with a chessboard/ChArUco board.
*/
ARUCO_CW_TOP_LEFT_CORNER
};
/** @brief Pose estimation parameters
*
* @param pattern Defines center this system and axes direction (default PatternPositionType::ARUCO_CCW_CENTER).
* @param useExtrinsicGuess Parameter used for SOLVEPNP_ITERATIVE. If true (1), the function uses the provided
* rvec and tvec values as initial approximations of the rotation and translation vectors, respectively, and further
* optimizes them (default false).
* @param solvePnPMethod Method for solving a PnP problem: see @ref calib3d_solvePnP_flags (default SOLVEPNP_ITERATIVE).
*
* @deprecated Use Board::matchImagePoints and cv::solvePnP
*
* @sa PatternPositionType, solvePnP()
*/
struct CV_EXPORTS_W_SIMPLE EstimateParameters {
CV_PROP_RW aruco::PatternPositionType pattern;
CV_PROP_RW bool useExtrinsicGuess;
CV_PROP_RW int solvePnPMethod;
CV_WRAP EstimateParameters();
};
/**
* @brief Calibrate a camera using aruco markers
*
* @param corners vector of detected marker corners in all frames.
* The corners should have the same format returned by detectMarkers (see #detectMarkers).
* @param ids list of identifiers for each marker in corners
* @param counter number of markers in each frame so that corners and ids can be split
* @param board Marker Board layout
* @param imageSize Size of the image used only to initialize the intrinsic camera matrix.
* @param cameraMatrix Output 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$ . If CV\_CALIB\_USE\_INTRINSIC\_GUESS
* and/or CV_CALIB_FIX_ASPECT_RATIO are specified, some or all of fx, fy, cx, cy must be
* initialized before calling the function.
* @param distCoeffs Output vector of distortion coefficients
* \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
* @param rvecs Output vector of rotation vectors (see Rodrigues ) estimated for each board view
* (e.g. std::vector<cv::Mat>>). That is, each k-th rotation vector together with the corresponding
* k-th translation vector (see the next output parameter description) brings the board pattern
* from the model coordinate space (in which object points are specified) to the world coordinate
* space, that is, a real position of the board pattern in the k-th pattern view (k=0.. *M* -1).
* @param tvecs Output vector of translation vectors estimated for each pattern view.
* @param stdDeviationsIntrinsics Output vector of standard deviations estimated for intrinsic parameters.
* Order of deviations values:
* \f$(f_x, f_y, c_x, c_y, k_1, k_2, p_1, p_2, k_3, k_4, k_5, k_6 , s_1, s_2, s_3,
* s_4, \tau_x, \tau_y)\f$ If one of parameters is not estimated, it's deviation is equals to zero.
* @param stdDeviationsExtrinsics Output vector of standard deviations estimated for extrinsic parameters.
* Order of deviations values: \f$(R_1, T_1, \dotsc , R_M, T_M)\f$ where M is number of pattern views,
* \f$R_i, T_i\f$ are concatenated 1x3 vectors.
* @param perViewErrors Output vector of average re-projection errors estimated for each pattern view.
* @param flags flags Different flags for the calibration process (see #calibrateCamera for details).
* @param criteria Termination criteria for the iterative optimization algorithm.
*
* This function calibrates a camera using an Aruco Board. The function receives a list of
* detected markers from several views of the Board. The process is similar to the chessboard
* calibration in calibrateCamera(). The function returns the final re-projection error.
*
* @deprecated Use Board::matchImagePoints and cv::solvePnP
*/
CV_EXPORTS_AS(calibrateCameraArucoExtended)
double calibrateCameraAruco(InputArrayOfArrays corners, InputArray ids, InputArray counter, const Ptr<Board> &board,
Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, OutputArray stdDeviationsIntrinsics,
OutputArray stdDeviationsExtrinsics, OutputArray perViewErrors, int flags = 0,
const TermCriteria& criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/** @overload
* @brief It's the same function as #calibrateCameraAruco but without calibration error estimation.
* @deprecated Use Board::matchImagePoints and cv::solvePnP
*/
CV_EXPORTS_W double calibrateCameraAruco(InputArrayOfArrays corners, InputArray ids, InputArray counter,
const Ptr<Board> &board, Size imageSize, InputOutputArray cameraMatrix,
InputOutputArray distCoeffs, OutputArrayOfArrays rvecs = noArray(),
OutputArrayOfArrays tvecs = noArray(), int flags = 0,
const TermCriteria& criteria = TermCriteria(TermCriteria::COUNT + TermCriteria::EPS,
30, DBL_EPSILON));
/**
* @brief Calibrate a camera using Charuco corners
*
* @param charucoCorners vector of detected charuco corners per frame
* @param charucoIds list of identifiers for each corner in charucoCorners per frame
* @param board Marker Board layout
* @param imageSize input image size
* @param cameraMatrix Output 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$ . If CV\_CALIB\_USE\_INTRINSIC\_GUESS
* and/or CV_CALIB_FIX_ASPECT_RATIO are specified, some or all of fx, fy, cx, cy must be
* initialized before calling the function.
* @param distCoeffs Output vector of distortion coefficients
* \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
* @param rvecs Output vector of rotation vectors (see Rodrigues ) estimated for each board view
* (e.g. std::vector<cv::Mat>>). That is, each k-th rotation vector together with the corresponding
* k-th translation vector (see the next output parameter description) brings the board pattern
* from the model coordinate space (in which object points are specified) to the world coordinate
* space, that is, a real position of the board pattern in the k-th pattern view (k=0.. *M* -1).
* @param tvecs Output vector of translation vectors estimated for each pattern view.
* @param stdDeviationsIntrinsics Output vector of standard deviations estimated for intrinsic parameters.
* Order of deviations values:
* \f$(f_x, f_y, c_x, c_y, k_1, k_2, p_1, p_2, k_3, k_4, k_5, k_6 , s_1, s_2, s_3,
* s_4, \tau_x, \tau_y)\f$ If one of parameters is not estimated, it's deviation is equals to zero.
* @param stdDeviationsExtrinsics Output vector of standard deviations estimated for extrinsic parameters.
* Order of deviations values: \f$(R_1, T_1, \dotsc , R_M, T_M)\f$ where M is number of pattern views,
* \f$R_i, T_i\f$ are concatenated 1x3 vectors.
* @param perViewErrors Output vector of average re-projection errors estimated for each pattern view.
* @param flags flags Different flags for the calibration process (see #calibrateCamera for details).
* @param criteria Termination criteria for the iterative optimization algorithm.
*
* This function calibrates a camera using a set of corners of a Charuco Board. The function
* receives a list of detected corners and its identifiers from several views of the Board.
* The function returns the final re-projection error.
*
* @deprecated Use CharucoBoard::matchImagePoints and cv::solvePnP
*/
CV_EXPORTS_AS(calibrateCameraCharucoExtended)
double calibrateCameraCharuco(InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds,
const Ptr<CharucoBoard> &board, Size imageSize, InputOutputArray cameraMatrix,
InputOutputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs,
OutputArray stdDeviationsIntrinsics, OutputArray stdDeviationsExtrinsics,
OutputArray perViewErrors, int flags = 0, const TermCriteria& criteria = TermCriteria(
TermCriteria::COUNT + TermCriteria::EPS, 30, DBL_EPSILON));
/**
* @brief It's the same function as #calibrateCameraCharuco but without calibration error estimation.
*
* @deprecated Use CharucoBoard::matchImagePoints and cv::solvePnP
*/
CV_EXPORTS_W double calibrateCameraCharuco(InputArrayOfArrays charucoCorners, InputArrayOfArrays charucoIds,
const Ptr<CharucoBoard> &board, Size imageSize,
InputOutputArray cameraMatrix, InputOutputArray distCoeffs,
OutputArrayOfArrays rvecs = noArray(),
OutputArrayOfArrays tvecs = noArray(), int flags = 0,
const TermCriteria& criteria=TermCriteria(TermCriteria::COUNT +
TermCriteria::EPS, 30, DBL_EPSILON));
//! @}
}
}
#endif

View File

@ -0,0 +1,62 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "precomp.hpp"
#include <opencv2/calib3d.hpp>
#include "charuco.hpp"
#include <opencv2/imgproc.hpp>
namespace cv {
namespace aruco {
using namespace std;
int interpolateCornersCharuco(InputArrayOfArrays _markerCorners, InputArray _markerIds,
InputArray _image, const Ptr<CharucoBoard> &_board,
OutputArray _charucoCorners, OutputArray _charucoIds,
InputArray _cameraMatrix, InputArray _distCoeffs, int minMarkers) {
CharucoParameters params;
params.minMarkers = minMarkers;
params.cameraMatrix = _cameraMatrix.getMat();
params.distCoeffs = _distCoeffs.getMat();
CharucoDetector detector(*_board, params);
vector<Mat> markerCorners;
_markerCorners.getMatVector(markerCorners);
detector.detectBoard(_image, _charucoCorners, _charucoIds, markerCorners, _markerIds.getMat());
return (int)_charucoIds.total();
}
void detectCharucoDiamond(InputArray _image, InputArrayOfArrays _markerCorners, InputArray _markerIds,
float squareMarkerLengthRate, OutputArrayOfArrays _diamondCorners, OutputArray _diamondIds,
InputArray _cameraMatrix, InputArray _distCoeffs, Ptr<Dictionary> dictionary) {
CharucoParameters params;
params.cameraMatrix = _cameraMatrix.getMat();
params.distCoeffs = _distCoeffs.getMat();
CharucoBoard board({3, 3}, squareMarkerLengthRate, 1.f, *dictionary);
CharucoDetector detector(board, params);
vector<Mat> markerCorners;
_markerCorners.getMatVector(markerCorners);
detector.detectDiamonds(_image, _diamondCorners, _diamondIds, markerCorners, _markerIds.getMat());
}
void drawCharucoDiamond(const Ptr<Dictionary> &dictionary, Vec4i ids, int squareLength, int markerLength,
OutputArray _img, int marginSize, int borderBits) {
CV_Assert(squareLength > 0 && markerLength > 0 && squareLength > markerLength);
CV_Assert(marginSize >= 0 && borderBits > 0);
// assign the charuco marker ids
vector<int> tmpIds(4);
for(int i = 0; i < 4; i++)
tmpIds[i] = ids[i];
// create a charuco board similar to a charuco marker and print it
CharucoBoard board(Size(3, 3), (float)squareLength, (float)markerLength, *dictionary, tmpIds);
Size outSize(3 * squareLength + 2 * marginSize, 3 * squareLength + 2 * marginSize);
board.generateImage(outSize, _img, marginSize, borderBits);
}
}
}

View File

@ -0,0 +1,110 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef OPENCV_CHARUCO_HPP
#define OPENCV_CHARUCO_HPP
#include <opencv2/core.hpp>
#include <vector>
#include "../aruco.hpp"
#include <opencv2/objdetect/charuco_detector.hpp>
#include "aruco_calib.hpp"
namespace cv {
namespace aruco {
//! @addtogroup aruco
//! @{
/**
* @brief Interpolate position of ChArUco board corners
* @param markerCorners vector of already detected markers corners. For each marker, its four
* corners are provided, (e.g std::vector<std::vector<cv::Point2f> > ). For N detected markers, the
* dimensions of this array should be Nx4. The order of the corners should be clockwise.
* @param markerIds list of identifiers for each marker in corners
* @param image input image necesary for corner refinement. Note that markers are not detected and
* should be sent in corners and ids parameters.
* @param board layout of ChArUco board.
* @param charucoCorners interpolated chessboard corners
* @param charucoIds interpolated chessboard corners identifiers
* @param cameraMatrix optional 3x3 floating-point camera matrix
* \f$A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$
* @param distCoeffs optional vector of distortion coefficients
* \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
* @param minMarkers number of adjacent markers that must be detected to return a charuco corner
*
* This function receives the detected markers and returns the 2D position of the chessboard corners
* from a ChArUco board using the detected Aruco markers. If camera parameters are provided,
* the process is based in an approximated pose estimation, else it is based on local homography.
* Only visible corners are returned. For each corner, its corresponding identifier is
* also returned in charucoIds.
* The function returns the number of interpolated corners.
*
* @deprecated Use CharucoDetector::detectBoard
*/
CV_EXPORTS_W int interpolateCornersCharuco(InputArrayOfArrays markerCorners, InputArray markerIds,
InputArray image, const Ptr<CharucoBoard> &board,
OutputArray charucoCorners, OutputArray charucoIds,
InputArray cameraMatrix = noArray(),
InputArray distCoeffs = noArray(), int minMarkers = 2);
/**
* @brief Detect ChArUco Diamond markers
*
* @param image input image necessary for corner subpixel.
* @param markerCorners list of detected marker corners from detectMarkers function.
* @param markerIds list of marker ids in markerCorners.
* @param squareMarkerLengthRate rate between square and marker length:
* squareMarkerLengthRate = squareLength/markerLength. The real units are not necessary.
* @param diamondCorners output list of detected diamond corners (4 corners per diamond). The order
* is the same than in marker corners: top left, top right, bottom right and bottom left. Similar
* format than the corners returned by detectMarkers (e.g std::vector<std::vector<cv::Point2f> > ).
* @param diamondIds ids of the diamonds in diamondCorners. The id of each diamond is in fact of
* type Vec4i, so each diamond has 4 ids, which are the ids of the aruco markers composing the
* diamond.
* @param cameraMatrix Optional camera calibration matrix.
* @param distCoeffs Optional camera distortion coefficients.
* @param dictionary dictionary of markers indicating the type of markers.
*
* This function detects Diamond markers from the previous detected ArUco markers. The diamonds
* are returned in the diamondCorners and diamondIds parameters. If camera calibration parameters
* are provided, the diamond search is based on reprojection. If not, diamond search is based on
* homography. Homography is faster than reprojection, but less accurate.
*
* @deprecated Use CharucoDetector::detectDiamonds
*/
CV_EXPORTS_W void detectCharucoDiamond(InputArray image, InputArrayOfArrays markerCorners,
InputArray markerIds, float squareMarkerLengthRate,
OutputArrayOfArrays diamondCorners, OutputArray diamondIds,
InputArray cameraMatrix = noArray(),
InputArray distCoeffs = noArray(),
Ptr<Dictionary> dictionary = makePtr<Dictionary>
(getPredefinedDictionary(PredefinedDictionaryType::DICT_4X4_50)));
/**
* @brief Draw a ChArUco Diamond marker
*
* @param dictionary dictionary of markers indicating the type of markers.
* @param ids list of 4 ids for each ArUco marker in the ChArUco marker.
* @param squareLength size of the chessboard squares in pixels.
* @param markerLength size of the markers in pixels.
* @param img output image with the marker. The size of this image will be
* 3*squareLength + 2*marginSize,.
* @param marginSize minimum margins (in pixels) of the marker in the output image
* @param borderBits width of the marker borders.
*
* This function return the image of a ChArUco marker, ready to be printed.
*
* @deprecated Use CharucoBoard::generateImage()
*/
CV_EXPORTS_W void drawCharucoDiamond(const Ptr<Dictionary> &dictionary, Vec4i ids, int squareLength,
int markerLength, OutputArray img, int marginSize = 0,
int borderBits = 1);
//! @}
}
}
#endif

View File

@ -0,0 +1,11 @@
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#ifndef __OPENCV_CCALIB_PRECOMP__
#define __OPENCV_CCALIB_PRECOMP__
#include <opencv2/core.hpp>
#include <vector>
#endif