ippe.h
Go to the documentation of this file.
1 #ifndef _IPPE_H_
2 #define _IPPE_H_
3 #include <opencv2/core/core.hpp>
4 
5 
6 //This is the core header file for IPPE. Infinitesimal Plane-based Pose Estimation (IPPE) is a very fast and accurate way to compute a camera's pose from a single image of a planar object using point correspondences. This has uses in several applications, including augmented reality, 3D tracking and pose estimation with planar markers, and 3D scene understanding.
7 //This package is free and covered by the BSD licence without any warranty. We hope you find this code useful and if so please cite our paper in your work:
8 
9 //@article{ year={2014}, issn={0920-5691}, journal={International Journal of Computer Vision}, volume={109}, number={3}, doi={10.1007/s11263-014-0725-5}, title={Infinitesimal Plane-Based Pose Estimation}, url={http://dx.doi.org/10.1007/s11263-014-0725-5}, publisher={Springer US}, keywords={Plane; Pose; SfM; PnP; Homography}, author={Collins, Toby and Bartoli, Adrien}, pages={252-286}, language={English} }
10 
11 //Please contact Toby (toby.collins@gmail.com) if you have any questions about the code, paper and IPPE.
12 
13 namespace IPPE {
14 //returns the two solutions
15 std::vector<cv::Mat> solvePnP(const std::vector<cv::Point3f> &objPoints,const std::vector<cv::Point2f> &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs);
16 
17 std::vector<std::pair<cv::Mat,double> > solvePnP_(const std::vector<cv::Point3f> &objPoints,const std::vector<cv::Point2f> &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs);
18 
45 void solvePoseOfCentredSquare(float squareLength, cv::InputArray imagePoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs,
46  cv::OutputArray _rvec1, cv::OutputArray _tvec1, float & reprojErr1, cv::OutputArray _rvec2, cv::OutputArray _tvec2, float & reprojErr2);
47 
48 
49 
59 int IPPEvalBestPose(cv::InputArray _R1,cv::InputArray _R2, cv::InputArray _t1,cv::InputArray _t2, cv::InputArray _objectPoints, cv::InputArray _undistortedPoints);
60 
68 float IPPEvalReprojectionError(cv::InputArray _R,cv::InputArray _t, cv::InputArray _objectPoints, cv::InputArray _undistortedPoints);
69 
70 
75 void IPPERot2vec(cv::InputArray _R, cv::OutputArray _r);
76 
83 void IPPComputeTranslation(cv::InputArray _objectPoints, cv::InputArray _imgPoints, cv::InputArray _R,cv::OutputArray _t);
84 
93 void IPPComputeRotations(double j00, double j01, double j10,double j11,double p,double q,cv::OutputArray _R1, cv::OutputArray _R2);
94 
106 void homographyFromSquarePoints(cv::InputArray _targetPts, double halfLength,cv::OutputArray _H);
107 
108 
109 }
110 #endif
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:55
void IPPERot2vec(cv::InputArray _R, cv::OutputArray _r)
Fast conversion from a rotation matrix to a rotation vector using Rodrigues&#39; formula.
Definition: ippe.h:13
void homographyFromSquarePoints(cv::InputArray _targetPts, double halfLength, cv::OutputArray _H)
Closed-form solution for the homography mapping with four corner correspondences of a square (it maps...
void solvePoseOfCentredSquare(float squareLength, cv::InputArray imagePoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs, cv::OutputArray _rvec1, cv::OutputArray _tvec1, float &reprojErr1, cv::OutputArray _rvec2, cv::OutputArray _tvec2, float &reprojErr2)
Finds the two possible poses of a square planar object given its four corner correspondences in an im...
int IPPEvalBestPose(cv::InputArray _R1, cv::InputArray _R2, cv::InputArray _t1, cv::InputArray _t2, cv::InputArray _objectPoints, cv::InputArray _undistortedPoints)
Determines which of the two pose solutions from IPPE has the lowest reprojection error.
float IPPEvalReprojectionError(cv::InputArray _R, cv::InputArray _t, cv::InputArray _objectPoints, cv::InputArray _undistortedPoints)
Determines the reprojection error of a pose solution.
void IPPComputeTranslation(cv::InputArray _objectPoints, cv::InputArray _imgPoints, cv::InputArray _R, cv::OutputArray _t)
Computes the translation solution for a given rotation solution.
void IPPComputeRotations(double j00, double j01, double j10, double j11, double p, double q, cv::OutputArray _R1, cv::OutputArray _R2)
Computes the two rotation solutions from the Jacobian of a homography matrix H. For highest accuracy ...
std::vector< std::pair< cv::Mat, double > > solvePnP_(const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
Definition: ippe.cpp:67


tuw_aruco
Author(s): Lukas Pfeifhofer
autogenerated on Mon Jun 10 2019 15:40:51