|
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 source points to target points). The source points are the four corners of a zero-centred squared defined by: point 0: [-squareLength / 2.0, squareLength / 2.0] point 1: [squareLength / 2.0, squareLength / 2.0] point 2: [squareLength / 2.0, -squareLength / 2.0] point 3: [-squareLength / 2.0, -squareLength / 2.0]. More...
|
|
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 the Jacobian should be computed at the centroid of the point correspondences (see the IPPE paper for the explaination of this). For a point (ux,uy) on the model plane, suppose the homography H maps (ux,uy) to a point (p,q) in the image (in normalised pixel coordinates). The Jacobian matrix [J00, J01; J10,J11] is the Jacobian of the mapping evaluated at (ux,uy). More...
|
|
void | IPPComputeTranslation (cv::InputArray _objectPoints, cv::InputArray _imgPoints, cv::InputArray _R, cv::OutputArray _t) |
| Computes the translation solution for a given rotation solution. More...
|
|
void | IPPERot2vec (cv::InputArray _R, cv::OutputArray _r) |
| Fast conversion from a rotation matrix to a rotation vector using Rodrigues' formula. More...
|
|
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. More...
|
|
float | IPPEvalReprojectionError (cv::InputArray _R, cv::InputArray _t, cv::InputArray _objectPoints, cv::InputArray _undistortedPoints) |
| Determines the reprojection error of a pose solution. More...
|
|
std::vector< cv::Mat > | solvePnP (const std::vector< cv::Point3f > &objPoints, const std::vector< cv::Point2f > &imgPoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs) |
|
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) |
|
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 image using IPPE. These poses are sorted so that the first one is the one with the lowest reprojection error. The second pose is needed if the problem is ambiguous. The problem is ambiguous when the projection of the model is close to affine, which in practice happens if it is small or viewed from a large distance. In these cases there are two pose solutions that can correctly align the correspondences (up to noise), so it is impossible to select the right one from just the reprojection error. IPPE gives you both the solutions, rather than just a single solution (which in ambiguous cases would be wrong 50% of the time). Geometrically, the two poses roughly correspond to a reflection of the model about a plane whose normal passes through the line-of-sight from the camera centre to the model's centre. For more details about these ambiguities, please refer to the IPPE paper. More...
|
|
void IPPE::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 the Jacobian should be computed at the centroid of the point correspondences (see the IPPE paper for the explaination of this). For a point (ux,uy) on the model plane, suppose the homography H maps (ux,uy) to a point (p,q) in the image (in normalised pixel coordinates). The Jacobian matrix [J00, J01; J10,J11] is the Jacobian of the mapping evaluated at (ux,uy).
- Parameters
-
j00 | Jacobian coefficent |
j01 | Jacobian coefficent |
j10 | Jacobian coefficent |
j11 | Jacobian coefficent |
p | the x coordinate of point (ux,uy) mapped into the image (undistorted and normalised position) |
q | the y coordinate of point (ux,uy) mapped into the image (undistorted and normalised position) |
void IPPE::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 image using IPPE. These poses are sorted so that the first one is the one with the lowest reprojection error. The second pose is needed if the problem is ambiguous. The problem is ambiguous when the projection of the model is close to affine, which in practice happens if it is small or viewed from a large distance. In these cases there are two pose solutions that can correctly align the correspondences (up to noise), so it is impossible to select the right one from just the reprojection error. IPPE gives you both the solutions, rather than just a single solution (which in ambiguous cases would be wrong 50% of the time). Geometrically, the two poses roughly correspond to a reflection of the model about a plane whose normal passes through the line-of-sight from the camera centre to the model's centre. For more details about these ambiguities, please refer to the IPPE paper.
It is possible to reject the second pose if its reprojection error is significantly worse than the first pose. The correct way to do this is with a likelihood ratio test (https://en.wikipedia.org/wiki/Likelihood-ratio_test).
- Parameters
-
squareLength | the squares's length (which is also it's width) in object coordinate units (e.g. millimeters, meters, etc.) The square is defined in object coordinates on the plane z=0 and centred at the origin. Therefore its four points in object coordinates are given by: point 0: [-squareLength / 2.0, squareLength / 2.0, 0] point 1: [squareLength / 2.0, squareLength / 2.0, 0] point 2: [squareLength / 2.0, -squareLength / 2.0, 0] point 3: [-squareLength / 2.0, -squareLength / 2.0, 0] |
imagePoints | Array of four corresponding image points, 1x4/4x1 2-channel. Note that the points should be ordered to correspond with points 0, 1, 2 and 3. |
cameraMatrix | Input camera matrix . |
distCoeffs | Input vector of distortion coefficients of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed. |
_rvec1 | Output rotation vector (see Rodrigues ) for first pose. That, together with tvec , brings points from the model coordinate system to the camera coordinate system. |
_tvec1 | Output translation vector for first pose. |
reprojErr1 | Output reprojection error of first pose |
_rvec2 | Output rotation vector (see Rodrigues ) for second pose. That, together with tvec , brings points from the model coordinate system to the camera coordinate system. |
_tvec2 | Output translation vector for second pose. |
reprojErr1 | Output reprojection error of second pose |