ippe.h
Go to the documentation of this file.
1 
18 // This is the core header file for IPPE. Infinitesimal Plane-based Pose Estimation (IPPE)
19 // is a very fast and accurate way to compute a camera's pose from a single image of a
20 // planar object using point correspondences. This has uses in several applications,
21 // including augmented reality, 3D tracking and pose estimation with planar markers, and
22 // 3D scene understanding. This package is free and covered by the BSD licence without any
23 // warranty. We hope you find this code useful and if so please cite our paper in your
24 // work:
25 
26 //@article{ year={2014}, issn={0920-5691}, journal={International Journal of Computer
27 //Vision}, volume={109}, number={3}, doi={10.1007/s11263-014-0725-5}, title={Infinitesimal
28 // Plane-Based Pose Estimation}, url={http://dx.doi.org/10.1007/s11263-014-0725-5},
29 // publisher={Springer US}, keywords={Plane; Pose; SfM; PnP; Homography}, author={Collins,
30 // Toby and Bartoli, Adrien}, pages={252-286}, language={English} }
31 
32 // Please contact Toby (toby.collins@gmail.com) if you have any questions about the code, paper and IPPE.
33 
34 
35 #ifndef _IPPE_H_
36 #define _IPPE_H_
37 
38 #include <opencv2/core.hpp>
39 #include <opencv2/calib3d.hpp>
40 #include "aruco_export.h"
41 #include <limits>
42 
43 #define IPPE_SMALL 1e-7 // a small constant used to test 'small' values close to zero.
44 
45 namespace aruco
46 {
47 // returns the two solutions
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);
54 ARUCO_EXPORT std::vector<std::pair<cv::Mat, double>> solvePnP_(
55  float size, const std::vector<cv::Point2f>& imgPoints, cv::InputArray cameraMatrix,
56  cv::InputArray distCoeffs);
57 
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);
62 
63 } // namespace aruco
64 namespace IPPE
65 {
66 
68 {
69 public:
73  PoseSolver();
74 
78  ~PoseSolver();
79 
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);
103 
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);
127 
134  void generateSquareObjectCorners3D(double squareLength, cv::OutputArray _objectPoints);
135 
143  void generateSquareObjectCorners2D(double squareLength, cv::OutputArray _objectPoints);
144 
153  double meanSceneDepth(cv::InputArray objectPoints, cv::InputArray rvec, cv::InputArray tvec);
154 
155 private:
168  void solveGeneric(cv::InputArray _objectPoints, cv::InputArray _normalizedImagePoints,
169  cv::OutputArray _Ma, cv::OutputArray _Mb);
170 
184  void solveCanonicalForm(cv::InputArray _canonicalObjPoints, cv::InputArray _normalizedInputPoints,
185  cv::InputArray _H, cv::OutputArray _Ma, cv::OutputArray _Mb);
186 
195  void computeTranslation(cv::InputArray _objectPoints, cv::InputArray _normalizedImgPoints,
196  cv::InputArray _R, cv::OutputArray _t);
197 
213  void computeRotations(double j00, double j01, double j10, double j11, double p,
214  double q, cv::OutputArray _R1, cv::OutputArray _R2);
215 
227  void homographyFromSquarePoints(cv::InputArray _targetPoints, double halfLength,
228  cv::OutputArray _H);
229 
235  void rot2vec(cv::InputArray _R, cv::OutputArray _r);
236 
246  void makeCanonicalObjectPoints(cv::InputArray _objectPoints,
247  cv::OutputArray _canonicalObjectPoints,
248  cv::OutputArray _MobjectPoints2Canonical);
249 
268  void evalReprojError(cv::InputArray _objectPoints, cv::InputArray _imagePoints,
269  cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs,
270  cv::InputArray _M, float& err);
271 
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);
299 
306  void rotateVec2ZAxis(cv::InputArray _a, cv::OutputArray _Ra);
307 
308 
317  bool computeObjextSpaceR3Pts(cv::InputArray _objectPoints, cv::OutputArray _R);
318 
326  bool computeObjextSpaceRSvD(cv::InputArray _objectPointsZeroMean, cv::OutputArray _R);
327 };
328 } // namespace IPPE
329 
330 namespace HomographyHO
331 {
332 
343 void homographyHO(cv::InputArray srcPoints, cv::InputArray targPoints, cv::OutputArray H);
344 
356 void normalizeDataIsotropic(cv::InputArray Data, cv::OutputArray DataN, cv::OutputArray T,
357  cv::OutputArray Ti);
358 } // namespace HomographyHO
359 
360 #endif
Definition: ippe.h:64
ARUCO_EXPORT std::vector< std::pair< cv::Mat, double > > solvePnP_(float size, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
Definition: ippe.cpp:115
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.
Definition: ippe.cpp:923
#define ARUCO_EXPORT
Definition: aruco_export.h:30
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&#39;Leary&#39;s m...
Definition: ippe.cpp:1041
std::vector< cv::Mat > solvePnP(const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
Definition: ippe.cpp:88


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Fri Nov 25 2022 04:02:23