#include <ippe.h>
Public Member Functions | |
void | generateSquareObjectCorners2D (double squareLength, cv::OutputArray _objectPoints) |
Generates the 4 object points of a square planar object, without including the z-component (which is z=0 for all points). More... | |
void | generateSquareObjectCorners3D (double squareLength, cv::OutputArray _objectPoints) |
Generates the 4 object points of a square planar object. More... | |
double | meanSceneDepth (cv::InputArray objectPoints, cv::InputArray rvec, cv::InputArray tvec) |
Computes the average depth of an object given its pose in camera coordinates. More... | |
PoseSolver () | |
PoseSolver constructor. More... | |
void | solveGeneric (cv::InputArray _objectPoints, 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 planar object given a set of correspondences and their respective reprojection errors. The poses are sorted with the first having the lowest reprojection error. More... | |
void | solveSquare (double 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 and their respective reprojection errors using IPPE. These poses are sorted so that the first one is the one with the lowest reprojection error. More... | |
~PoseSolver () | |
PoseSolver destructor. More... | |
Private Member Functions | |
bool | computeObjextSpaceR3Pts (cv::InputArray _objectPoints, cv::OutputArray _R) |
Computes the rotation _R that rotates the object points to the plane z=0. This uses the cross-product method with the first three object points. More... | |
bool | computeObjextSpaceRSvD (cv::InputArray _objectPointsZeroMean, cv::OutputArray _R) |
computeObjextSpaceRSvD Computes the rotation _R that rotates the object points to the plane z=0. This uses the cross-product method with the first three object points. More... | |
void | computeRotations (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 at a point (ux,uy) on the object plane. For highest accuracy the Jacobian should be computed at the centroid of the point correspondences (see the IPPE paper for the explanation of this). For a point (ux,uy) on the object plane, suppose the homography H maps (ux,uy) to a point (p,q) in the image (in normalized pixel coordinates). The Jacobian matrix [J00, J01; J10,J11] is the Jacobian of the mapping evaluated at (ux,uy). More... | |
void | computeTranslation (cv::InputArray _objectPoints, cv::InputArray _normalizedImgPoints, cv::InputArray _R, cv::OutputArray _t) |
Computes the translation solution for a given rotation solution. More... | |
void | evalReprojError (cv::InputArray _objectPoints, cv::InputArray _imagePoints, cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs, cv::InputArray _M, float &err) |
Evaluates the Root Mean Squared (RMS) reprojection error of a pose solution. More... | |
void | homographyFromSquarePoints (cv::InputArray _targetPoints, 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 | makeCanonicalObjectPoints (cv::InputArray _objectPoints, cv::OutputArray _canonicalObjectPoints, cv::OutputArray _MobjectPoints2Canonical) |
Takes a set of planar object points and transforms them to 'canonical' object coordinates This is when they have zero mean and are on the plane z=0. More... | |
void | rot2vec (cv::InputArray _R, cv::OutputArray _r) |
Fast conversion from a rotation matrix to a rotation vector using Rodrigues' formula. More... | |
void | rotateVec2ZAxis (cv::InputArray _a, cv::OutputArray _Ra) |
Finds the rotation _Ra that rotates a vector _a to the z axis (0,0,1) More... | |
void | solveCanonicalForm (cv::InputArray _canonicalObjPoints, cv::InputArray _normalizedInputPoints, cv::InputArray _H, cv::OutputArray _Ma, cv::OutputArray _Mb) |
Finds the two possible poses of a planar object in its canonical position, given a set of correspondences in normalized pixel coordinates. These poses are NOT sorted on reprojection error. Note that the returned poses are object-to-camera transforms, and not camera-to-object transforms. More... | |
void | solveGeneric (cv::InputArray _objectPoints, cv::InputArray _normalizedImagePoints, cv::OutputArray _Ma, cv::OutputArray _Mb) |
Finds the two possible poses of a planar object given a set of correspondences in normalized pixel coordinates. These poses are NOT sorted on reprojection error. Note that the returned poses are object-to-camera transforms, and not camera-to-object transforms. More... | |
void | sortPosesByReprojError (cv::InputArray _objectPoints, cv::InputArray _imagePoints, cv::InputArray _cameraMatrix, cv::InputArray _distCoeffs, cv::InputArray _Ma, cv::InputArray _Mb, cv::OutputArray _M1, cv::OutputArray _M2, float &err1, float &err2) |
Sorts two pose solutions according to their RMS reprojection error (lowest first). More... | |
IPPE::PoseSolver::PoseSolver | ( | ) |
PoseSolver constructor.
IPPE::PoseSolver::~PoseSolver | ( | ) |
PoseSolver destructor.
|
private |
Computes the rotation _R that rotates the object points to the plane z=0. This uses the cross-product method with the first three object points.
_objectPoints | Array of N>=3 coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double) where N is the number of points |
_R | Rotation Mat: 3x3 (double) |
|
private |
computeObjextSpaceRSvD Computes the rotation _R that rotates the object points to the plane z=0. This uses the cross-product method with the first three object points.
_objectPointsZeroMean | zero-meaned co=planar object points: 3xN matrix (double) where N>=3 |
_R | Rotation Mat: 3x3 (double) |
|
private |
Computes the two rotation solutions from the Jacobian of a homography matrix H at a point (ux,uy) on the object plane. For highest accuracy the Jacobian should be computed at the centroid of the point correspondences (see the IPPE paper for the explanation of this). For a point (ux,uy) on the object plane, suppose the homography H maps (ux,uy) to a point (p,q) in the image (in normalized pixel coordinates). The Jacobian matrix [J00, J01; J10,J11] is the Jacobian of the mapping evaluated at (ux,uy).
j00 | Homography jacobian coefficent at (ux,uy) |
j01 | Homography jacobian coefficent at (ux,uy) |
j10 | Homography jacobian coefficent at (ux,uy) |
j11 | Homography jacobian coefficent at (ux,uy) |
p | the x coordinate of point (ux,uy) mapped into the image (undistorted and normalized position) |
q | the y coordinate of point (ux,uy) mapped into the image (undistorted and normalized position) |
|
private |
Computes the translation solution for a given rotation solution.
_objectPoints | Array of corresponding object points, 1xN/Nx1 3-channel where N is the number of points |
_normalizedImagePoints | Array of corresponding image points (undistorted), 1xN/Nx1 2-channel where N is the number of points |
_R | Rotation solution (3x1 rotation vector) |
_t | Translation solution Translation solution (3x1 rotation vector) |
|
private |
Evaluates the Root Mean Squared (RMS) reprojection error of a pose solution.
_objectPoints | Array of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double) where N is the number of points |
_imagePoints | Array of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates. |
_cameraMatrix | Intrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray(). |
_distCoeffs | Intrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray(). |
_M | Pose matrix from 3D object to camera coordinates: 4x4 1-channel (double) |
err | RMS reprojection error |
void IPPE::PoseSolver::generateSquareObjectCorners2D | ( | double | squareLength, |
cv::OutputArray | _objectPoints | ||
) |
Generates the 4 object points of a square planar object, without including the z-component (which is z=0 for all points).
squareLength | The square's length (which is also it's width) in object coordinate units (e.g. millimeters, meters, etc.) |
_objectPoints | Set of 4 object points (1x4 2-channel double) |
void IPPE::PoseSolver::generateSquareObjectCorners3D | ( | double | squareLength, |
cv::OutputArray | _objectPoints | ||
) |
|
private |
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].
_targetPoints | Array of four corresponding target points, 1x4/4x1 2-channel. Note that the points should be ordered to correspond with points 0, 1, 2 and 3. |
halfLength | the square's half length (i.e. squareLength/2.0) |
_H | Homograhy mapping the source points to the target points, 3x3 single channel |
|
private |
Takes a set of planar object points and transforms them to 'canonical' object coordinates This is when they have zero mean and are on the plane z=0.
_objectPoints | Array of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double) where N is the number of points |
_canonicalObjectPoints | Object points in canonical coordinates 1xN/Nx1 2-channel (double) |
_MobjectPoints2Canonical | Transform matrix mapping _objectPoints to _canonicalObjectPoints: 4x4 1-channel (double) |
double IPPE::PoseSolver::meanSceneDepth | ( | cv::InputArray | objectPoints, |
cv::InputArray | rvec, | ||
cv::InputArray | tvec | ||
) |
|
private |
|
private |
|
private |
Finds the two possible poses of a planar object in its canonical position, given a set of correspondences in normalized pixel coordinates. These poses are NOT sorted on reprojection error. Note that the returned poses are object-to-camera transforms, and not camera-to-object transforms.
_canonicalObjPoints | Array of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (double) where N is the number of points |
_normalizedInputPoints | Array of corresponding image points in normalized pixel coordinates, 1xN/Nx1 2-channel (double) where N is the number of points |
_H | Homography mapping canonicalObjPoints to normalizedInputPoints. |
_Ma | |
_Mb |
void IPPE::PoseSolver::solveGeneric | ( | cv::InputArray | _objectPoints, |
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 planar object given a set of correspondences and their respective reprojection errors. The poses are sorted with the first having the lowest reprojection error.
_objectPoints | Array of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double) where N is the number of points |
_imagePoints | Array of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates. |
_cameraMatrix | Intrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray() |
_distCoeffs | Intrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray() |
_rvec1 | First rotation solution (3x1 rotation vector) |
_tvec1 | First translation solution (3x1 vector) |
reprojErr1 | Reprojection error of first solution |
_rvec2 | Second rotation solution (3x1 rotation vector) |
_tvec2 | Second translation solution (3x1 vector) |
reprojErr2 | Reprojection error of second solution |
|
private |
Finds the two possible poses of a planar object given a set of correspondences in normalized pixel coordinates. These poses are NOT sorted on reprojection error. Note that the returned poses are object-to-camera transforms, and not camera-to-object transforms.
_objectPoints | Array of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double). |
_normalizedImagePoints | Array of corresponding image points in normalized pixel coordinates, 1xN/Nx1 2-channel (float or double). |
_Ma | First pose solution (unsorted) |
_Mb | Second pose solution (unsorted) |
void IPPE::PoseSolver::solveSquare | ( | double | 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 and their respective reprojection errors using IPPE. These poses are sorted so that the first one is the one with the lowest reprojection error.
_squareLength | The square's length (which is also it's width) in object coordinate units (e.g. millimeters, meters, etc.) |
_imagePoints | Array of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates. |
_cameraMatrix | Intrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray() |
_distCoeffs | Intrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray() |
_rvec1 | First rotation solution (3x1 rotation vector) |
_tvec1 | First translation solution (3x1 vector) |
reprojErr1 | Reprojection error of first solution |
_rvec2 | Second rotation solution (3x1 rotation vector) |
_tvec2 | Second translation solution (3x1 vector) |
reprojErr2 | Reprojection error of second solution |
|
private |
Sorts two pose solutions according to their RMS reprojection error (lowest first).
_objectPoints | Array of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double) where N is the number of points |
_imagePoints | Array of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates. |
_cameraMatrix | Intrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray(). |
_distCoeffs | Intrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray(). |
_Ma | Pose matrix 1: 4x4 1-channel |
_Mb | Pose matrix 2: 4x4 1-channel |
_M1 | Member of (Ma,Mb} with lowest RMS reprojection error. Performs deep copy. |
_M2 | Member of (Ma,Mb} with highest RMS reprojection error. Performs deep copy. |
err1 | RMS reprojection error of _M1 |
err2 | RMS reprojection error of _M2 |