3 #include <opencv2/core/core.hpp>    15 std::vector<cv::Mat> 
solvePnP(
const std::vector<cv::Point3f> &objPoints,
const  std::vector<cv::Point2f> &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs);
    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);
    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);
    59 int IPPEvalBestPose(cv::InputArray _R1,cv::InputArray _R2, cv::InputArray _t1,cv::InputArray _t2, cv::InputArray _objectPoints, cv::InputArray _undistortedPoints);
    68 float IPPEvalReprojectionError(cv::InputArray _R,cv::InputArray _t, cv::InputArray _objectPoints, cv::InputArray _undistortedPoints);
    75 void IPPERot2vec(cv::InputArray _R, cv::OutputArray _r);
    83 void IPPComputeTranslation(cv::InputArray _objectPoints, cv::InputArray _imgPoints, cv::InputArray _R,cv::OutputArray _t);
    93 void IPPComputeRotations(
double j00, 
double j01, 
double j10,
double j11,
double p,
double q,cv::OutputArray _R1, cv::OutputArray _R2);
 std::vector< cv::Mat > solvePnP(const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs)
void IPPERot2vec(cv::InputArray _R, cv::OutputArray _r)
Fast conversion from a rotation matrix to a rotation vector using Rodrigues' formula. 
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)