38 #include <opencv2/core.hpp> 39 #include <opencv2/calib3d.hpp> 43 #define IPPE_SMALL 1e-7 // a small constant used to test 'small' values close to zero. 48 std::vector<cv::Mat>
solvePnP(
const std::vector<cv::Point3f>& objPoints,
49 const std::vector<cv::Point2f>& imgPoints,
50 cv::InputArray cameraMatrix, cv::InputArray distCoeffs);
51 void solvePnP(
const std::vector<cv::Point3f>& objPoints,
52 const std::vector<cv::Point2f>& imgPoints, cv::InputArray cameraMatrix,
53 cv::InputArray distCoeffs, cv::Mat& rvec, cv::Mat& tvec);
55 float size,
const std::vector<cv::Point2f>& imgPoints, cv::InputArray cameraMatrix,
56 cv::InputArray distCoeffs);
58 std::vector<std::pair<cv::Mat, double>>
solvePnP_(
const std::vector<cv::Point3f>& objPoints,
59 const std::vector<cv::Point2f>& imgPoints,
60 cv::InputArray cameraMatrix,
61 cv::InputArray distCoeffs);
99 void solveGeneric(cv::InputArray _objectPoints, cv::InputArray _imagePoints,
100 cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs,
101 cv::OutputArray _rvec1, cv::OutputArray _tvec1,
float& reprojErr1,
102 cv::OutputArray _rvec2, cv::OutputArray _tvec2,
float& reprojErr2);
123 void solveSquare(
double squareLength, cv::InputArray _imagePoints,
124 cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs,
125 cv::OutputArray _rvec1, cv::OutputArray _tvec1,
float& reprojErr1,
126 cv::OutputArray _rvec2, cv::OutputArray _tvec2,
float& reprojErr2);
134 void generateSquareObjectCorners3D(
double squareLength, cv::OutputArray _objectPoints);
143 void generateSquareObjectCorners2D(
double squareLength, cv::OutputArray _objectPoints);
153 double meanSceneDepth(cv::InputArray objectPoints, cv::InputArray rvec, cv::InputArray tvec);
168 void solveGeneric(cv::InputArray _objectPoints, cv::InputArray _normalizedImagePoints,
169 cv::OutputArray _Ma, cv::OutputArray _Mb);
184 void solveCanonicalForm(cv::InputArray _canonicalObjPoints, cv::InputArray _normalizedInputPoints,
185 cv::InputArray _H, cv::OutputArray _Ma, cv::OutputArray _Mb);
195 void computeTranslation(cv::InputArray _objectPoints, cv::InputArray _normalizedImgPoints,
196 cv::InputArray _R, cv::OutputArray _t);
213 void computeRotations(
double j00,
double j01,
double j10,
double j11,
double p,
214 double q, cv::OutputArray _R1, cv::OutputArray _R2);
227 void homographyFromSquarePoints(cv::InputArray _targetPoints,
double halfLength,
235 void rot2vec(cv::InputArray _R, cv::OutputArray _r);
246 void makeCanonicalObjectPoints(cv::InputArray _objectPoints,
247 cv::OutputArray _canonicalObjectPoints,
248 cv::OutputArray _MobjectPoints2Canonical);
268 void evalReprojError(cv::InputArray _objectPoints, cv::InputArray _imagePoints,
269 cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs,
270 cv::InputArray _M,
float& err);
295 void sortPosesByReprojError(cv::InputArray _objectPoints, cv::InputArray _imagePoints,
296 cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs,
297 cv::InputArray _Ma, cv::InputArray _Mb, cv::OutputArray _M1,
298 cv::OutputArray _M2,
float& err1,
float& err2);
306 void rotateVec2ZAxis(cv::InputArray _a, cv::OutputArray _Ra);
317 bool computeObjextSpaceR3Pts(cv::InputArray _objectPoints, cv::OutputArray _R);
326 bool computeObjextSpaceRSvD(cv::InputArray _objectPointsZeroMean, cv::OutputArray _R);
343 void homographyHO(cv::InputArray srcPoints, cv::InputArray targPoints, cv::OutputArray H);
ARUCO_EXPORT std::vector< std::pair< cv::Mat, double > > solvePnP_(float size, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
void normalizeDataIsotropic(cv::InputArray Data, cv::OutputArray DataN, cv::OutputArray T, cv::OutputArray Ti)
Performs data normalization before homography estimation. For details see Hartley, R., Zisserman, A., Multiple View Geometry in Computer Vision, Cambridge University Press, Cambridge, 2001.
void homographyHO(cv::InputArray srcPoints, cv::InputArray targPoints, cv::OutputArray H)
Computes the best-fitting homography matrix from source to target points using Harker and O'Leary's m...
std::vector< cv::Mat > solvePnP(const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)