This class implements self-calibration for multiple views.
More...
#include <MultipleViewGeometry.h>
|
static bool | findCommonIntrinsicsFromProjectionMatricesIF (const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, SquareMatrix3 &cameraIntrinsics, SquareMatrix4 *Q=nullptr, SquareMatrix3 *omega=nullptr) |
| Estimate the common intrinsic camera matrix based on an Absolute Conic omega (ω):
omega = K * K^T — (ω_j = ω = KK^T).
|
|
static bool | findCommonIntrinsicsFromProjectionMatricesIF (const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, const unsigned int imageWidth, const unsigned int imageHeight, SquareMatrix3 &cameraIntrinsics, SquareMatrix4 *Q=nullptr, SquareMatrix3 *omega=nullptr) |
| Estimate a common intrinsic camera matrix based on an Absolute Conic ω:
ω_j = ω = KK^T.
|
|
static bool | determineAbsoluteDualQuadricLinearIF (const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, SquareMatrix4 &matrixQ, const unsigned int imageWidth, const unsigned int imageHeight, bool equalFxFy=true) |
| Estimates the absolute dual quadric Q_infinity (Q∞) from several projection-pose matrices by solving a linear system:
omega = P_j * Q_infinity * P_j^T — (ω_j = P_j * Q∞ * P_j^T).
|
|
static bool | intrinsicsFromAbsoluteDualQuadricIF (const SquareMatrix4 &symmetricQ, const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, SquareMatrix3 *intrinsics) |
| Determines individual intrinsic camera matrices from a known absolute dual quadric Q_infinity (Q∞) and corresponding camera-projection-pose matrices:
omega_j = P_j * Q_infinity * P_J^T = K_j * K_j^T — (ω_j = P_j * Q∞ * P_J^T = K_j * K_j^T).
|
|
static bool | transformProjectiveToMetricIF (const SquareMatrix4 &Q, const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, HomogenousMatrix4 *iFlippedMetricProjectionMatrices, SquareMatrix4 *transformation=nullptr) |
| Transforms a projective reconstruction towards a metric reconstruction.
|
|
static bool | metricProjectionMatricesToPosesIF (const ConstIndexedAccessor< HomogenousMatrix4 > &metricProjectionsIF, const SquareMatrix3 &intrinsic, HomogenousMatrix4 *posesIF) |
| Decomposes metric camera projection matrices all containing/sharing the same known camera matrix (intrinsic camera matrix) into (inverted and flipped) camera poses simply by applying the inverted intrinsic matrix.
|
|
This class implements self-calibration for multiple views.
◆ createLinearSystemForAbsoluteDualQuadric()
static Matrix Ocean::Geometry::AutoCalibration::createLinearSystemForAbsoluteDualQuadric |
( |
const unsigned int |
omegaRowIndex, |
|
|
const unsigned int |
omegaColumnIndex, |
|
|
const HomogenousMatrix4 & |
iFlippedProjectionMatrix |
|
) |
| |
|
staticprivate |
Creates a line for the linear system for the zero condition of absolute conic ω(i, j).
The line contains values of the upper triangle entities of absolute dual quadric matrix Q_infinity — (Q∞): ω(i, j) = [P * Q∞ * P^T](i, j) = 0
- Parameters
-
omegaRowIndex | Row index of absolute conic ω |
omegaColumnIndex | Column index of absolute conic ω |
iFlippedProjectionMatrix | The inverted and flipped camera projection matrix, must be valid |
- Returns
- A line matrix [1x10] containing the values of the upper triangle entities of the symmetric matrix Q∞
◆ determineAbsoluteDualQuadricLinearIF()
static bool Ocean::Geometry::AutoCalibration::determineAbsoluteDualQuadricLinearIF |
( |
const ConstIndexedAccessor< HomogenousMatrix4 > & |
iFlippedProjectionMatrices, |
|
|
SquareMatrix4 & |
matrixQ, |
|
|
const unsigned int |
imageWidth, |
|
|
const unsigned int |
imageHeight, |
|
|
bool |
equalFxFy = true |
|
) |
| |
|
static |
Estimates the absolute dual quadric Q_infinity (Q∞) from several projection-pose matrices by solving a linear system:
omega = P_j * Q_infinity * P_j^T — (ω_j = P_j * Q∞ * P_j^T).
Here, we assume no skew and the principle point in the center of the camera frame.
- Parameters
-
iFlippedProjectionMatrices | The inverted and flipped camera projection matrices [K | P0], [K | P1], [K | P2], ..., with Pi = [Ri | ti], at least 3 |
matrixQ | Resulting absolute dual quadric Q_infinity — (Q∞) |
imageWidth | Width of the camera frame in pixel, with range [1, infinity) |
imageHeight | Height of the camera frame in pixel, with range [1, infinity) |
equalFxFy | Forces equal focal length in both dimension |
- Returns
- True, if succeeded
- See also
- findCommonIntrinsicsFromProjectionMatricesIF()
◆ findCommonIntrinsicsFromProjectionMatricesIF() [1/2]
Estimate a common intrinsic camera matrix based on an Absolute Conic ω:
ω_j = ω = KK^T.
Solve a linear system by assuming zero skew, a known principle point (centered in the camera frame) and equal focal length for each ω
- Parameters
-
iFlippedProjectionMatrices | Inverted and flipped camera projection matrices [K | P0], [K | P1], [K | P2], ..., with Pi = [Ri | ti], at least 3 |
imageWidth | Width of the camera frame in pixel, with range [1, infinity) |
imageHeight | Height of the camera frame in pixel, with range [1, infinity) |
cameraIntrinsics | Resulting camera intrinsics matrix |
Q | Resulting absolute dual quadric Q∞, optionally |
omega | Resulting absolute conic &omega, optionally |
- Returns
- True, if succeeded
- See also
- findAbsoluteDualQuadricLinear()
◆ findCommonIntrinsicsFromProjectionMatricesIF() [2/2]
Estimate the common intrinsic camera matrix based on an Absolute Conic omega (ω):
omega = K * K^T — (ω_j = ω = KK^T).
Solve a linear system by assuming equal entities in each ω
- Parameters
-
iFlippedProjectionMatrices | The inverted and flipped camera projection matrices [K * P0], [K * P1], [K * P2], ..., with Pi = [Ri | ti], at least 3 |
cameraIntrinsics | Resulting intrinsic camera matrix |
Q | Optional resulting absolute dual quadric Q∞ |
omega | Optional resulting absolute conic &omega |
- Returns
- True, if succeeded
- See also
- findAbsoluteDualQuadricLinear()
◆ getTransformProjectiveToMetricMatrix()
static bool Ocean::Geometry::AutoCalibration::getTransformProjectiveToMetricMatrix |
( |
const SquareMatrix4 & |
Q, |
|
|
SquareMatrix4 & |
transformation |
|
) |
| |
|
staticprotected |
Determines the perspective transformation to get a metric reconstruction.
Q∞ = H * Î * H^T, factorized by eigen decomposition.
- Parameters
-
Q | Absolute dual quadric Q∞ |
transformation | Resulting perspective transformation H |
- Returns
- True, if succeeded
- See also
- transformProjectiveToMetric()
◆ intrinsicsFromAbsoluteDualQuadricIF()
Determines individual intrinsic camera matrices from a known absolute dual quadric Q_infinity (Q∞) and corresponding camera-projection-pose matrices:
omega_j = P_j * Q_infinity * P_J^T = K_j * K_j^T — (ω_j = P_j * Q∞ * P_J^T = K_j * K_j^T).
The Cholesky decomposition is applied to factorize omega into K.
- Parameters
-
symmetricQ | The absolute dual quadric q_infinity which is symmetric |
iFlippedProjectionMatrices | The inverted and flipped camera projection pose matrices |
intrinsics | The resulting intrinsic camera matrices, one for each projection pose matrix |
- Returns
- True, if succeeded
- See also
- findAbsoluteDualQuadricLinear()
-
transformProjectionsZeroPrinciplePoint()
◆ metricProjectionMatricesToPosesIF()
Decomposes metric camera projection matrices all containing/sharing the same known camera matrix (intrinsic camera matrix) into (inverted and flipped) camera poses simply by applying the inverted intrinsic matrix.
Based on the following equation: P_metric = K * [R t] we can determine the camera poses by: [R t] = K^-1 * p_metric.
- Parameters
-
metricProjectionsIF | The inverted and flipped metric camera projection matrices |
intrinsic | The already known intrinsic camera matrix K |
posesIF | The resulting inverted and flipped camera poses, one for each given camera projection matrix |
- Returns
- True, if succeeded
- See also
- transformProjectiveToMetric().
◆ transformProjectionsZeroPrinciplePoint()
Transforms an inverted and flipped camera projection matrix P = K * [R|t] in a way that the principle point of the camera profile (the camera intrinsics) is zero.
P' = T * P.
- Parameters
-
iFlippedProjectionMatrices | Inverted and flipped camera projection matrices, at least one |
imageWidth | Width of image in pixel, with range [1, infinity) |
imageHeight | Height of image in pixel, with range [1, infinity) |
iFlippedNormalizedProjectionMatrices | Resulting normalized inverted and flipped camera projection matrices, one for each given camera projection matrix |
backTransformation | Optional resulting back transformation matrix T^-1 |
- Returns
- True, if succeeded
- See also
- transformProjectiveToMetric()
◆ transformProjectiveToMetricIF()
Transforms a projective reconstruction towards a metric reconstruction.
Q∞ = H * Î * H^T.
P_metric = P * H.
- Parameters
-
Q | Absolute dual quadric Q∞ |
iFlippedProjectionMatrices | The camera projection matrices (inverted flipped) |
iFlippedMetricProjectionMatrices | Resulting metric projection matrices (inverted flipped) |
transformation | Optional resulting perspective transformation matrix |
- Returns
- True, if succeeded
- See also
- getTransformProjectiveToMetricMatrix()
◆ upperTriangleCholeskyDecomposition()
static bool Ocean::Geometry::AutoCalibration::upperTriangleCholeskyDecomposition |
( |
const SquareMatrix3 & |
omega, |
|
|
SquareMatrix3 & |
cameraIntrinsic |
|
) |
| |
|
staticprivate |
Performs the decomposition of an absolute conic omega (ω) into the intrinsic camera matrix:
omega = K * K^T — (ω = K * K^T), where K is the camera matrix (which is a upper triangular matrix).
The Cholesky decomposition is applied.
- Parameters
-
omega | The (symmetric) absolute conic to be decomposed (ω) |
cameraIntrinsic | The resulting intrinsic camera matrix |
- Returns
- True, if succeeded
The documentation for this class was generated from the following file: