Public Member Functions | Private Member Functions | List of all members
IPPE::PoseSolver Class Reference

#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...
 

Detailed Description

Definition at line 67 of file ippe.h.

Constructor & Destructor Documentation

◆ PoseSolver()

IPPE::PoseSolver::PoseSolver ( )

PoseSolver constructor.

Definition at line 151 of file ippe.cpp.

◆ ~PoseSolver()

IPPE::PoseSolver::~PoseSolver ( )

PoseSolver destructor.

Definition at line 155 of file ippe.cpp.

Member Function Documentation

◆ computeObjextSpaceR3Pts()

bool IPPE::PoseSolver::computeObjextSpaceR3Pts ( cv::InputArray  _objectPoints,
cv::OutputArray  _R 
)
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.

Parameters
_objectPointsArray of N>=3 coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double) where N is the number of points
_RRotation Mat: 3x3 (double)
Returns
success (true) or failure (false)

Definition at line 1213 of file ippe.cpp.

◆ computeObjextSpaceRSvD()

bool IPPE::PoseSolver::computeObjextSpaceRSvD ( cv::InputArray  _objectPointsZeroMean,
cv::OutputArray  _R 
)
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.

Parameters
_objectPointsZeroMeanzero-meaned co=planar object points: 3xN matrix (double) where N>=3
_RRotation Mat: 3x3 (double)
Returns
success (true) or failure (false)

Definition at line 1275 of file ippe.cpp.

◆ computeRotations()

void IPPE::PoseSolver::computeRotations ( double  j00,
double  j01,
double  j10,
double  j11,
double  p,
double  q,
cv::OutputArray  _R1,
cv::OutputArray  _R2 
)
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).

Parameters
j00Homography jacobian coefficent at (ux,uy)
j01Homography jacobian coefficent at (ux,uy)
j10Homography jacobian coefficent at (ux,uy)
j11Homography jacobian coefficent at (ux,uy)
pthe x coordinate of point (ux,uy) mapped into the image (undistorted and normalized position)
qthe y coordinate of point (ux,uy) mapped into the image (undistorted and normalized position)

Definition at line 537 of file ippe.cpp.

◆ computeTranslation()

void IPPE::PoseSolver::computeTranslation ( cv::InputArray  _objectPoints,
cv::InputArray  _normalizedImgPoints,
cv::InputArray  _R,
cv::OutputArray  _t 
)
private

Computes the translation solution for a given rotation solution.

Parameters
_objectPointsArray of corresponding object points, 1xN/Nx1 3-channel where N is the number of points
_normalizedImagePointsArray of corresponding image points (undistorted), 1xN/Nx1 2-channel where N is the number of points
_RRotation solution (3x1 rotation vector)
_tTranslation solution Translation solution (3x1 rotation vector)

Definition at line 440 of file ippe.cpp.

◆ evalReprojError()

void IPPE::PoseSolver::evalReprojError ( cv::InputArray  _objectPoints,
cv::InputArray  _imagePoints,
cv::InputArray  _cameraMatrix,
cv::InputArray  _distCoeffs,
cv::InputArray  _M,
float &  err 
)
private

Evaluates the Root Mean Squared (RMS) reprojection error of a pose solution.

Parameters
_objectPointsArray 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
_imagePointsArray of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates.
_cameraMatrixIntrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray().
_distCoeffsIntrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray().
_MPose matrix from 3D object to camera coordinates: 4x4 1-channel (double)
errRMS reprojection error

Definition at line 846 of file ippe.cpp.

◆ generateSquareObjectCorners2D()

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).

Parameters
squareLengthThe square's length (which is also it's width) in object coordinate units (e.g. millimeters, meters, etc.)
_objectPointsSet of 4 object points (1x4 2-channel double)

Definition at line 366 of file ippe.cpp.

◆ generateSquareObjectCorners3D()

void IPPE::PoseSolver::generateSquareObjectCorners3D ( double  squareLength,
cv::OutputArray  _objectPoints 
)

Generates the 4 object points of a square planar object.

Parameters
squareLengthThe square's length (which is also it's width) in object coordinate units (e.g. millimeters, meters, etc.)
_objectPointsSet of 4 object points (1x4 3-channel double)

Definition at line 356 of file ippe.cpp.

◆ homographyFromSquarePoints()

void IPPE::PoseSolver::homographyFromSquarePoints ( cv::InputArray  _targetPoints,
double  halfLength,
cv::OutputArray  _H 
)
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].

Parameters
_targetPointsArray 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.
halfLengththe square's half length (i.e. squareLength/2.0)
_HHomograhy mapping the source points to the target points, 3x3 single channel

Definition at line 660 of file ippe.cpp.

◆ makeCanonicalObjectPoints()

void IPPE::PoseSolver::makeCanonicalObjectPoints ( cv::InputArray  _objectPoints,
cv::OutputArray  _canonicalObjectPoints,
cv::OutputArray  _MobjectPoints2Canonical 
)
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.

Parameters
_objectPointsArray 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
_canonicalObjectPointsObject points in canonical coordinates 1xN/Nx1 2-channel (double)
_MobjectPoints2CanonicalTransform matrix mapping _objectPoints to _canonicalObjectPoints: 4x4 1-channel (double)

Definition at line 734 of file ippe.cpp.

◆ meanSceneDepth()

double IPPE::PoseSolver::meanSceneDepth ( cv::InputArray  objectPoints,
cv::InputArray  rvec,
cv::InputArray  tvec 
)

Computes the average depth of an object given its pose in camera coordinates.

Parameters
objectPointsObject points defined in 3D object space
rvecRotation component of pose
tvecTranslation component of pose
Returns
: average depth of the object

Definition at line 376 of file ippe.cpp.

◆ rot2vec()

void IPPE::PoseSolver::rot2vec ( cv::InputArray  _R,
cv::OutputArray  _r 
)
private

Fast conversion from a rotation matrix to a rotation vector using Rodrigues' formula.

Parameters
_RInput rotation matrix, 3x3 1-channel (double)
_rOutput rotation vector, 3x1/1x3 1-channel (double)

Definition at line 409 of file ippe.cpp.

◆ rotateVec2ZAxis()

void IPPE::PoseSolver::rotateVec2ZAxis ( cv::InputArray  _a,
cv::OutputArray  _Ra 
)
private

Finds the rotation _Ra that rotates a vector _a to the z axis (0,0,1)

Parameters
_avector: 3x1 mat (double)
_RaRotation: 3x3 mat (double)

Definition at line 1169 of file ippe.cpp.

◆ solveCanonicalForm()

void IPPE::PoseSolver::solveCanonicalForm ( cv::InputArray  _canonicalObjPoints,
cv::InputArray  _normalizedInputPoints,
cv::InputArray  _H,
cv::OutputArray  _Ma,
cv::OutputArray  _Mb 
)
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.

Parameters
_canonicalObjPointsArray of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (double) where N is the number of points
_normalizedInputPointsArray of corresponding image points in normalized pixel coordinates, 1xN/Nx1 2-channel (double) where N is the number of points
_HHomography mapping canonicalObjPoints to normalizedInputPoints.
_Ma
_Mb

Definition at line 255 of file ippe.cpp.

◆ solveGeneric() [1/2]

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.

Parameters
_objectPointsArray 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
_imagePointsArray of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates.
_cameraMatrixIntrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray()
_distCoeffsIntrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray()
_rvec1First rotation solution (3x1 rotation vector)
_tvec1First translation solution (3x1 vector)
reprojErr1Reprojection error of first solution
_rvec2Second rotation solution (3x1 rotation vector)
_tvec2Second translation solution (3x1 vector)
reprojErr2Reprojection error of second solution

Definition at line 159 of file ippe.cpp.

◆ solveGeneric() [2/2]

void IPPE::PoseSolver::solveGeneric ( cv::InputArray  _objectPoints,
cv::InputArray  _normalizedImagePoints,
cv::OutputArray  _Ma,
cv::OutputArray  _Mb 
)
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.

Parameters
_objectPointsArray of 4 or more coplanar object points defined in object coordinates. 1xN/Nx1 3-channel (float or double).
_normalizedImagePointsArray of corresponding image points in normalized pixel coordinates, 1xN/Nx1 2-channel (float or double).
_MaFirst pose solution (unsorted)
_MbSecond pose solution (unsorted)

Definition at line 197 of file ippe.cpp.

◆ solveSquare()

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.

Parameters
_squareLengthThe square's length (which is also it's width) in object coordinate units (e.g. millimeters, meters, etc.)
_imagePointsArray of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates.
_cameraMatrixIntrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray()
_distCoeffsIntrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray()
_rvec1First rotation solution (3x1 rotation vector)
_tvec1First translation solution (3x1 vector)
reprojErr1Reprojection error of first solution
_rvec2Second rotation solution (3x1 rotation vector)
_tvec2Second translation solution (3x1 vector)
reprojErr2Reprojection error of second solution

Definition at line 297 of file ippe.cpp.

◆ sortPosesByReprojError()

void IPPE::PoseSolver::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 
)
private

Sorts two pose solutions according to their RMS reprojection error (lowest first).

Parameters
_objectPointsArray 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
_imagePointsArray of corresponding image points, 1xN/Nx1 2-channel. This can either be in pixel coordinates or normalized pixel coordinates.
_cameraMatrixIntrinsic camera matrix (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray().
_distCoeffsIntrinsic camera distortion vector (same definition as OpenCV). If _imagePoints is in normalized pixel coordinates you must set _cameraMatrix = cv::noArray().
_MaPose matrix 1: 4x4 1-channel
_MbPose matrix 2: 4x4 1-channel
_M1Member of (Ma,Mb} with lowest RMS reprojection error. Performs deep copy.
_M2Member of (Ma,Mb} with highest RMS reprojection error. Performs deep copy.
err1RMS reprojection error of _M1
err2RMS reprojection error of _M2

Definition at line 895 of file ippe.cpp.


The documentation for this class was generated from the following files:


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:45