![]() |
University of Murcia ![]() |
Projective GeometryFunctions related to Projective Geometry.
More... |
Functions | |
QVMatrix | ComputeProjectiveHomography (const QList< QPointFMatching > &matchings) |
Obtains a planar homography from two lists of corresponding points. | |
QVMatrix | cvFindFundamentalMat (const QList< QPointFMatching > &matchings) |
Obtains the fundamental matrix between two images, using the 8 point algorithm. | |
QVMatrix | ComputeEuclideanHomography (const QList< QPointFMatching > &matchings) |
Obtain an euclidean mapping for a set of inter-image point matchings. | |
QPointF | ApplyHomography (const QVMatrix &homography, const QPointF &point) |
Obtains the homogenized coordinates of a point mapped using an homography transformation. | |
QList< QPointF > | ApplyHomography (const QVMatrix &homography, const QList< QPointF > &sourcePoints) |
Obtains the homogenized coordinates of a set of points mapped using an homography transformation. | |
double | HomographyTestError (const QVMatrix &homography) |
Function to test if a 3x3 matrix corresponds to an homography. | |
void | GetExtrinsicCameraMatrixFromHomography (const QVMatrix &K, const QVMatrix &H, QVMatrix &M4x4) |
void | GetDirectIntrinsicCameraMatrixFromHomography (const QVMatrix &H, QVMatrix &K) |
Diagonal intrinsic camera matrix calibration. | |
void | CalibrateCameraFromPlanarHomography (const QVMatrix &H, QVMatrix &K, QVMatrix &Rt) |
Diagonal intrinsic camera matrix calibration. | |
void | GetPinholeCameraIntrinsicsFromPlanarHomography (const QVMatrix &H, QVMatrix &K, const int iterations=100, const double maxGradientNorm=1e-3, const double step=0.01, const double tol=1e-4) |
Obtains the intrinsic camera matrix from a planar homography. | |
QList< QVMatrix > | getCanonicalCameraMatricesFromEssentialMatrix (const QVMatrix &E) |
Obtains the canonical matrices corresponding to an essential matrix. | |
QVMatrix | getEssentialMatrixFromCanonicalCameraMatrix (const QVMatrix &P) |
Obtains the essential matrix corresponding to a canonical camera matrix. | |
QVMatrix | getCameraMatrixFrom2D3DPointCorrespondences (const QList< QPointF > &points2d, const QList< QV3DPointF > &points3d) |
Obtains the canonical camera matrix corresponding to a set of 3D point to image point matchings. | |
QV3DPointF | triangulate3DPointFrom2DProjectionsAndCanonicalCameraMatrices (const QList< QPointF > &points, const QList< QVMatrix > &Plist) |
Recovers the location of a 3D point from its projection on several images and their corresponding canonical camera matrices. |
Projective Geometry models the principles of perspective, and provides important results for Computer Vision. Some naming conventions in the API of this module follows:
Matrix represents the intrinsic camera parameters, and matrix
the extrinsic camera configuration. The projection camera matrix
models the linear relationship between the location of a point in the 3D space
and its corresponding pixel in an image
:
The essential matrix relates the normalized locations of corresponding points at two different images:
GetExtrinsicCameraMatrixFromHomography
GetDirectIntrinsicCameraMatrixFromHomography
QList<QPointF> ApplyHomography | ( | const QVMatrix & | homography, | |
const QList< QPointF > & | sourcePoints | |||
) |
Obtains the homogenized coordinates of a set of points mapped using an homography transformation.
This function applies a transformation homography over a set of points. For further info about this mapping see function ApplyHomography(const QVMatrix &, const QPointF &).
homography | The homography transformation matrix | |
sourcePoints | Points to apply the homography transformation |
Definition at line 297 of file qvprojective.cpp.
QPointF ApplyHomography | ( | const QVMatrix & | homography, | |
const QPointF & | point | |||
) |
Obtains the homogenized coordinates of a point mapped using an homography transformation.
This function obtains the point which holds the following equation:
Where and
are the input transformation homography and point respectively. Matrix
must be of size
.
homography | The homography transformation matrix | |
point | Point to apply the homography transformation |
Definition at line 286 of file qvprojective.cpp.
Referenced by ApplyHomography().
Diagonal intrinsic camera matrix calibration.
This function obtains a diagonal intrinsic camera matrix, consisting on the focal distance only. This matrix is such that
Where is a rotation matrix. This matrix is obtained with a minimization process, so its result is more precise than that obtained with GetDirectIntrinsicCameraMatrixFromHomography function.
Definition at line 343 of file qvprojective.cpp.
QVMatrix ComputeEuclideanHomography | ( | const QList< QPointFMatching > & | matchings | ) |
Obtain an euclidean mapping for a set of inter-image point matchings.
This function obtains an euclidean mapping between the source an destination locations of a set of point matchings. The mapping is returned as a matrix which can be multiplied to the source location of each mapping point in homogeneous coordinates, obtaining a location close to the destination location from the matching.
Definition at line 229 of file qvprojective.cpp.
QVMatrix ComputeProjectiveHomography | ( | const QList< QPointFMatching > & | matchings | ) |
Obtains a planar homography from two lists of corresponding points.
This function obtains the planar homography which maps the location of the points from a source plane to a destination plane. One of the planes can be the image plane as well.
The function returns the matrix corresponding to the planar homography, from a list of four or more point correspondences between the location of those points at the source plane and their location in the destination plane.
This function can be used to compute a rectification homography, which can be used to obtain a frontal view of any planar figure appearing in an image. The following code and images shows this effect:
Image on the left is the original picture obtained with a pin-hole camera. Image on the right was obtained aplying a rectification homography to the pixels in the original image. This rectification homography is obtained using the function ComputeProjectiveHomography with the four point correspondences between the points in the images featured with yellow dots:
QList< QPair<QPointF, QPointF> > matchings; matchings.append(QPair<QPointF, QPointF>(QPointF(-171,109), QPointF(-100,+100))); matchings.append(QPair<QPointF, QPointF>(QPointF(-120,31), QPointF(-100,-100))); matchings.append(QPair<QPointF, QPointF>(QPointF(117,53), QPointF(+100,-100))); matchings.append(QPair<QPointF, QPointF>(QPointF(11,115), QPointF(+100,+100))); const QVMatrix H = ComputeProjectiveHomography(matchings);
The obtained matrix holds the following equation:
Also for each point matching contained in the matchings list, the following equation holds.
or
In C++ source code:
QPair<QPointF, QPointF> matching; foreach(matching, matchings) { const QVVector p_0 = QVVector::homogeneousCoordinates(matching.first), p_1 = QVVector::homogeneousCoordinates(matching.second); std::cout << "p1 x H p0 =" << (p_1 ^ H*p_0) << std::endl; }
The printed values are close to 0.
The location at the rectified version of an image corresponding to pixel
at the original version of the image can be obtained given the rectification homography
using the following C++ code:
QPointF p_1 = H * QVVector::homogeneousCoordinates(p_0);
Or the ApplyHomography functions.
matchings | list of point matchings from the original location, to the destination location. |
Definition at line 93 of file qvprojective.cpp.
QVMatrix cvFindFundamentalMat | ( | const QList< QPointFMatching > & | matchings | ) |
Obtains the fundamental matrix between two images, using the 8 point algorithm.
This function performs point normalization to robustly obtain the F matrix.
matchings | list of 8 point matchings |
Definition at line 153 of file qvprojective.cpp.
Referenced by cvFindFundamentalMat().
QVMatrix getCameraMatrixFrom2D3DPointCorrespondences | ( | const QList< QPointF > & | points2d, | |
const QList< QV3DPointF > & | points3d | |||
) |
Obtains the canonical camera matrix corresponding to a set of 3D point to image point matchings.
The following formula models the relation between a set of points from the 3D world and their projections
at an image:
This function uses a DLT to obtain the camera matrix from a given set of 3D points and their corresponding image points.
points2d | List containing the points from the image. | |
points3d | List containing the 3D points. |
Definition at line 455 of file qvprojective.cpp.
Obtains the canonical matrices corresponding to an essential matrix.
See section 9.6.2 from Multiple View Geometry in Computer Vision.
E | The input essential matrix. |
Definition at line 435 of file qvprojective.cpp.
Diagonal intrinsic camera matrix calibration.
This function obtains a diagonal intrinsic camera matrix, consisting on the focal distance only. This matrix is such that
Where is a rotation matrix. This function returns a direct approximation for the
matrix.
Definition at line 327 of file qvprojective.cpp.
Referenced by CalibrateCameraFromPlanarHomography().
Obtains the essential matrix corresponding to a canonical camera matrix.
This method estimates the essential matrix of a two view scenario, provided the second camera matrix , considering the first camera matrix as the identity:
See section 9.6.1 from Multiple View Geometry in Computer Vision.
P | The input canonical matrix. |
Definition at line 450 of file qvprojective.cpp.
void GetPinholeCameraIntrinsicsFromPlanarHomography | ( | const QVMatrix & | H, | |
QVMatrix & | K, | |||
const int | iterations = 100 , |
|||
const double | maxGradientNorm = 1e-3 , |
|||
const double | step = 0.01 , |
|||
const double | tol = 1e-4 | |||
) |
Obtains the intrinsic camera matrix from a planar homography.
This functions obtains the intrinsic calibration matrix corresponding to a simple pinhole camera model. The intrinsic camera matrix has only one free parameter, related to the focal distance of the camera:
This function should receive a planar homography corresponding to the mapping of a set of know template points, to an image frame captured with the camera containing a view of that template.
The following is an example of a full intrinsic camera calibration, knowing a set of point matchings between the template image and the input image read from the camera:
[...] QList< QPointFMatching > matchings; matchings.append(QPointFMatching(QPointF(-171,109), QPointF(-100,+100))); matchings.append(QPointFMatching(QPointF(-120,31), QPointF(-100,-100))); matchings.append(QPointFMatching(QPointF(117,53), QPointF(+100,-100))); matchings.append(QPointFMatching(QPointF(11,115), QPointF(+100,+100))); QVMatrix H, K; H = ComputeProjectiveHomography(matchings); GetPinholeCameraIntrinsicsFromPlanarHomography(H, K); [...]
For further understanding of the planar homography calibration process, see ComputeProjectiveHomography function documentation.
H | Input planar homography. | |
K | Matrix to store the intrinsic camera matrix | |
iterations | Cumber of iterations to perform camera calibration | |
maxGradientNorm | Minimal value of the gradient size (norm 2) to stop the minimization when reached. | |
step | Corresponds to parameter step for the gsl_multimin_fdfminimizer_set function. | |
tol | Corresponds to parameter tol for the gsl_multimin_fdfminimizer_set function. |
Definition at line 400 of file qvprojective.cpp.
double HomographyTestError | ( | const QVMatrix & | homography | ) |
Function to test if a 3x3 matrix corresponds to an homography.
Every matrix which holds a perspective deformation from one plane to another should validate some constrains. The most important is that its two first columns should be perpendicular, and with a similar size, because for the matrix to correspond to an homography, they should be contained in a base of a rotated coordinate system. Given the following homography matrix:
The error value returned by this function for it will be:
That error is a measure of the difference of sizes between the norm of the two column vectors of the homography, corresponding to the two first columns of the rotation matrix, and their dot product. When both values are close to zero, the matrix corresponds to an homography, and it won't otherwise.
A good method to prove that a matrix corresponds to an homography using this function, can be done testing the return value with a threshold of aproximately 0.3. If the return value of this function for a matrix is lower than this threshold, that matrix is likely to correspond to an homography, and is not likely to correspond otherwise.
homography | a possible homography matrix. |
Definition at line 305 of file qvprojective.cpp.
QV3DPointF triangulate3DPointFrom2DProjectionsAndCanonicalCameraMatrices | ( | const QList< QPointF > & | points, | |
const QList< QVMatrix > & | Plist | |||
) |
Recovers the location of a 3D point from its projection on several images and their corresponding canonical camera matrices.
Given the projection formula:
The location of the 3D point can be triangulated with its projection on two or more images.
This function triangulates the location of a 3D point from the locations of two or more image projections
and the corresponding canonical camera matrices for these images
.
The method used is described at section 12.2 from Multiple View Geometry in Computer Vision.
points | List containing the points from the image. | |
Plist | List containing the canonical camera matrices. |
Definition at line 487 of file qvprojective.cpp.