Ocean
Loading...
Searching...
No Matches
MultipleViewGeometry.h
Go to the documentation of this file.
1/*
2 * Copyright (c) Meta Platforms, Inc. and affiliates.
3 *
4 * This source code is licensed under the MIT license found in the
5 * LICENSE file in the root directory of this source tree.
6 */
7
8#ifndef META_OCEAN_GEOMETRY_MULTIPLE_VIEW_GEOMETRY_H
9#define META_OCEAN_GEOMETRY_MULTIPLE_VIEW_GEOMETRY_H
10
13
14#include "ocean/math/Matrix.h"
15#include "ocean/math/Line2.h"
18#include "ocean/math/Vector3.h"
19
20#include <vector>
21
22namespace Ocean
23{
24
25namespace Geometry
26{
27
28/**
29 * This class implements epipolar geometry functions for multiple views.
30 * @ingroup geometry
31 */
32class OCEAN_GEOMETRY_EXPORT MultipleViewGeometry
33{
34 public:
35
36 /**
37 * Definition of a trifocal tensor matrix.
38 */
40 {
41 public:
42
43 /**
44 * Creates a new tensor object without initialization.
45 */
46 inline TrifocalTensor();
47
48 /**
49 * Creates a new tensor object by three given sub-matrices.
50 * @param matrix0 The first matrix of the new tensor
51 * @param matrix1 The second matrix of the new tensor
52 * @param matrix2 The third matrix of the new tensor
53 */
54 inline TrifocalTensor(const SquareMatrix3& matrix0, const SquareMatrix3& matrix1, const SquareMatrix3& matrix2);
55
56 /**
57 * Creates a new tensor object by three given sub-matrices.
58 * @param matrices The three matrix of the new tensor, must not be nullptr
59 */
60 explicit inline TrifocalTensor(const SquareMatrix3* matrices);
61
62 /**
63 * Element operator.
64 * Beware: No range check will be done!
65 * @param index Index of the matrix to return [0, 2]
66 * @return Specified sub-matrix
67 */
68 inline const SquareMatrix3& operator[](const unsigned int index) const;
69
70 /**
71 * Element operator.
72 * Beware: No range check will be done!
73 * @param index Index of the matrix to return [0, 2]
74 * @return Specified sub-matrix
75 */
76 inline SquareMatrix3& operator[](const unsigned int index);
77
78 /**
79 * Data operator returning the pointer to the first matrix of this tensor.
80 * @return The pointer of the first matrix
81 */
82 inline const SquareMatrix3* operator()() const;
83
84 /**
85 * Data operator returning the pointer to the first matrix of this tensor.
86 * @return The pointer of the first matrix
87 */
88 inline SquareMatrix3* operator()();
89
90 protected:
91
92 /// The three 3x3 matrices of this tensor.
93 SquareMatrix3 tensorMatrices[3];
94 };
95
96 public:
97
98 /**
99 * Computes geometric valid camera projection matrices which are determined up to a common 3d projection transformation. <br>
100 * The calculation uses 6 point correspondences in which three of them are not collinear in any view
101 * The projection matrices are defined in inverted flipped coordinates system and are necessary metric and orthogonally:
102 * x_k = P_k * X.
103 * @param points1 Image points of first view
104 * @param points2 Image points of second view
105 * @param points3 Image points of third view
106 * @param correspondences Number of point correspondences (at least 6)
107 * @param iFlippedProjectionMatrix1 Resulting camera projection matrix of first view (inverted flipped)
108 * @param iFlippedProjectionMatrix2 Resulting camera projection matrix of second view (inverted flipped)
109 * @param iFlippedProjectionMatrix3 Resulting camera projection matrix of third view (inverted flipped)
110 * @param squaredSuccessThreshold Threshold indicating successful matrices determination, optionally
111 * @param squaredProjectionError Squared back-projection error, optionally
112 * @return True, if succeeded and back-projection error is below threshold (note: a valid 3d scene is also maybe given with a higher error)
113 * @see projectiveReconstructionFrom6PointsIF()
114 * @see calibrateFromProjectionsMatricesIF()
115 */
116 static bool projectiveReconstructionFrom6PointsIF(const ImagePoint* points1, const ImagePoint* points2, const ImagePoint* points3, const size_t correspondences, HomogenousMatrix4& iFlippedProjectionMatrix1, HomogenousMatrix4& iFlippedProjectionMatrix2, HomogenousMatrix4& iFlippedProjectionMatrix3, const Scalar squaredSuccessThreshold = (2.5 * 2.5), Scalar* squaredProjectionError = nullptr);
117
118 /**
119 * Computes geometric valid camera projection matrices which are determined up to a common 3d projection transformation.
120 * The calculation uses 6 point correspondences in which three of them are not collinear in any view
121 * The projection matrices are defined in inverted flipped coordinates system and are not metric and orthogonally:
122 * x_k = P_k * X.
123 * @param imagePointsPerPose Image points per view (at least 3 views and at least 6 point correspondences)
124 * @param posesIF Resulting camera projection matrices per view (inverted flipped)
125 * @param squaredSuccessThreshold Threshold indicating successful matrices determination, optionally
126 * @param squaredProjectionError Squared back-projection error, optionally
127 * @return True, if succeeded and back-projection error is below threshold (note: a valid 3d scene is also maybe given with a higher error)
128 * @see projectiveReconstructionFrom6PointsIF()
129 * @see calibrateFromProjectionsMatricesIF()
130 */
131 static bool projectiveReconstructionFrom6PointsIF(const ConstIndexedAccessor<ImagePoints>& imagePointsPerPose, NonconstIndexedAccessor<HomogenousMatrix4>* posesIF, const Scalar squaredSuccessThreshold = Scalar(2.5 * 2.5), Scalar* squaredProjectionError = nullptr);
132
133 /**
134 * The normalized linear algorithm of computation of trifocal tensor.
135 * Calculates the trifocal tensor by three sets of at least seven corresponding image points and generates geometric valid camera projection matrices.
136 * The projection matrices are defined in inverted flipped coordinates system and are not metric and orthogonally:
137 * x_k = P_k * X.
138 * @param points1 Image points of first view
139 * @param points2 Image points of second view
140 * @param points3 Image points of third view
141 * @param correspondences Number of point correspondences (at least 7)
142 * @param iFlippedProjectionMatrix1 Resulting camera projection matrix of first view (inverted flipped)
143 * @param iFlippedProjectionMatrix2 Resulting camera projection matrix of second view (inverted flipped)
144 * @param iFlippedProjectionMatrix3 Resulting camera projection matrix of third view (inverted flipped)
145 * @param trifocalTensor Optional pointer to resulting trifocal tensor
146 * @return True, if succeeded
147 * @see calibrateFromProjectionsMatricesIF()
148 */
149 static bool trifocalTensorIF(const ImagePoint* points1, const ImagePoint* points2, const ImagePoint* points3, const size_t correspondences, HomogenousMatrix4& iFlippedProjectionMatrix1, HomogenousMatrix4& iFlippedProjectionMatrix2, HomogenousMatrix4& iFlippedProjectionMatrix3, TrifocalTensor* trifocalTensor = nullptr);
150
151 /**
152 * Calibrate multiple projection matrices from a single camera.
153 * The projection matrices are transformed into metric transformation matrix using absolute conic &omega; and absolute dual quadric Q&infin;: <br>
154 * &omega; = P * Q&infin; * P^T.<br>
155 * Q&infin; = H * Î * H^T.<br>
156 * P_metric = P * H.<br>
157 * The camera intrinsics are determined by Cholesky decomposition of absolute conic &omega; = K * K^T.
158 * @param iFlippedProjectionMatrices The camera projection matrices (at least 3, inverted flipped)
159 * @param imageWidth Width of image
160 * @param imageHeight Height of image
161 * @param cameraIntrinsic The resulting intrinsic camera matrix
162 * @param iFlippedPoses Resulting inverted and flipped camera poses, one for each given camera projection matrix
163 * @return True, if succeeded
164 * @see calibrateFromProjectionsMatricesIF()
165 */
166 static bool calibrateFromProjectionsMatricesIF(const ConstIndexedAccessor<HomogenousMatrix4>& iFlippedProjectionMatrices, const unsigned int imageWidth, const unsigned int imageHeight, SquareMatrix3& cameraIntrinsic, HomogenousMatrix4* iFlippedPoses);
167
168 /**
169 * Calibrate three projection matrices from a single camera.
170 * The projection matrices are transformed into metric transformation matrix using absolute conic &omega; and absolute dual quadric Q&infin;: <br>
171 * &omega; = P * Q&infin; * P^T.<br>
172 * Q&infin; = H * Î * H^T.<br>
173 * P_metric = P * H.<br>
174 * The camera intrinsics are determined by Cholesky decomposition of absolute conic &omega; = KK^T.
175 * @param iFlippedProjectionMatrix1 First camera projection matrices (inverted flipped)
176 * @param iFlippedProjectionMatrix2 Second camera projection matrices (inverted flipped)
177 * @param iFlippedProjectionMatrix3 Third camera projection matrices (inverted flipped)
178 * @param imageWidth Width of image
179 * @param imageHeight Height of image
180 * @param cameraIntrinsics Resulting camera intrinsics matrix
181 * @param iFlippedPose1 Resulting first camera pose (inverted flipped)
182 * @param iFlippedPose2 Resulting second camera pose (inverted flipped)
183 * @param iFlippedPose3 Resulting third camera pose (inverted flipped)
184 * @return True, if succeeded
185 * @see calibrateFromProjectionsMatricesIF()
186 */
187 static bool calibrateFromProjectionsMatricesIF(const HomogenousMatrix4& iFlippedProjectionMatrix1, const HomogenousMatrix4& iFlippedProjectionMatrix2, const HomogenousMatrix4& iFlippedProjectionMatrix3, const unsigned int imageWidth, const unsigned int imageHeight, SquareMatrix3& cameraIntrinsics, HomogenousMatrix4& iFlippedPose1, HomogenousMatrix4& iFlippedPose2, HomogenousMatrix4& iFlippedPose3);
188
189 protected:
190
191 /**
192 * The normalized linear algorithm of computation of trifocal tensor.
193 * Calculates the trifocal tensor by three sets of at least seven corresponding image points.
194 * @param points1 Image points of first set
195 * @param points2 Image points of second set
196 * @param points3 Image points of third set
197 * @param correspondences Number of point correspondences (at least 7)
198 * @param trifocal Resulting trifocal tensor matrices
199 * @return True, if succeeded
200 */
201 static bool trifocalTensorNormalizedLinear(const ImagePoint* points1, const ImagePoint* points2, const ImagePoint* points3, const size_t correspondences, TrifocalTensor& trifocal);
202
203 /**
204 * Computing a geometric valid trifocal tensor minimizing algebraic error.
205 * Calculates the trifocal tensor by three sets of at least seven corresponding image points.
206 * @param points1 Image points of first set
207 * @param points2 Image points of second set
208 * @param points3 Image points of third set
209 * @param correspondences Number of point correspondences (at least 7)
210 * @param trifocal Resulting trifocal tensor matrices
211 * @return True, if succeeded
212 */
213 static bool trifocalTensorMinimizingError(const ImagePoint* points1, const ImagePoint* points2, const ImagePoint* points3, const size_t correspondences, TrifocalTensor& trifocal);
214
215 /**
216 * Calculates the trifocal tensor by two projection matrix given:
217 * P_1 = [I | 0], P_2 = [A | a4], P_3 = [B | b4] and P = C * [Rt]
218 * @param iFlippedProjectionMatrixB projection matrix P_2 in homogeneous format
219 * @param iFlippedProjectionMatrixC projection matrix P_3 in homogeneous format
220 * @param trifocal Resulting trifocal tensor matrices
221 * @return True, if succeeded
222 */
223 static bool trifocalTensorFromProjectionMatrices(const HomogenousMatrix4& iFlippedProjectionMatrixB, const HomogenousMatrix4& iFlippedProjectionMatrixC, TrifocalTensor& trifocal);
224
225 /**
226 * Calculates the trifocal tensor by three projection matrix given:
227 * P_1 = [A | a4], P_2 = [B | b4], P_3 = [C | c4] and P = CameraInstrinsics * [Rt]
228 * @param iFlippedProjectionMatrixA projection matrix P_1 in homogeneous format
229 * @param iFlippedProjectionMatrixB projection matrix P_2 in homogeneous format
230 * @param iFlippedProjectionMatrixC projection matrix P_3 in homogeneous format
231 * @param trifocal Resulting trifocal tensor matrices
232 * @return True, if succeeded
233 */
234 static bool trifocalTensorFromProjectionMatrices(const HomogenousMatrix4& iFlippedProjectionMatrixA, const HomogenousMatrix4& iFlippedProjectionMatrixB, const HomogenousMatrix4& iFlippedProjectionMatrixC, TrifocalTensor& trifocal);
235
236 /**
237 * Calculates the normalized epipoles of second and third view from trifocal tensor
238 * @param trifocal Trifocal tensor matrices
239 * @param normedEpipole2 Resulting (normalized) epipole in second view
240 * @param normedEpipole3 Resulting (normalized) epipole in third view
241 * @return True, if succeeded
242 */
243 static bool epipoles(const TrifocalTensor& trifocal, Vector3& normedEpipole2, Vector3& normedEpipole3);
244
245 /**
246 * Calculates the normalized epipoles of second and third view from trifocal tensor for inverted flipped cameras
247 * @param trifocal Trifocal tensor matrices
248 * @param iFlippedNormedEpipole2 Resulting (normalized) epipole in second view
249 * @param iFlippedNormedEpipole3 Resulting (normalized) epipole in third view
250 * @return True, if succeeded
251 */
252 static bool epipolesIF(const TrifocalTensor& trifocal, Vector3& iFlippedNormedEpipole2, Vector3& iFlippedNormedEpipole3);
253
254 /**
255 * Calculates the fundamental matrices of second view and third view from trifocal tensor
256 * @param trifocal Trifocal tensor matrices
257 * @param iFlippedEpipole2 Epipole in second view
258 * @param iFlippedEpipole3 Epipole in third view
259 * @param fundamental21 Resulting fundamental matrix between second view and first view
260 * @param fundamental31 Resulting fundamental matrix between third view and first view
261 * @return True, if succeeded
262 */
263 static bool fundamentalMatricesIF(const TrifocalTensor& trifocal, const Vector3& iFlippedEpipole2, const Vector3& iFlippedEpipole3, SquareMatrix3& fundamental21, SquareMatrix3& fundamental31);
264
265 /**
266 * Calculates the camera projection matrices of second and third view.
267 * The matrices are determined only up to a common projective transformation of 3-space.
268 * The projection matrix of first camera must be P_0 = [I | 0]
269 * @param trifocal Trifocal tensor matrices
270 * @param iFlippedNormedEpipole2 Normalized epipole in second view
271 * @param iFlippedNormedEpipole3 Normalized epipole in third view
272 * @param iFlippedProjectionMatrix2 Resulting camera projection matrices of second view (determined only up to a common projective 3d transformation)
273 * @param iFlippedProjectionMatrix3 Resulting camera projection matrices of third view (determined only up to a common projective 3d transformation)
274 * @return True, if succeeded
275 */
276 static bool cameraProjectionMatricesIF(const TrifocalTensor& trifocal, const Vector3& iFlippedNormedEpipole2, const Vector3& iFlippedNormedEpipole3, HomogenousMatrix4& iFlippedProjectionMatrix2, HomogenousMatrix4& iFlippedProjectionMatrix3);
277
278 /**
279 * Calculates the normalized epipoles of second and third view from trifocal tensor
280 * @param trifocal1 First trifocal tensor matrix T_1
281 * @param trifocal2 Second trifocal tensor matrix T_2
282 * @param trifocal3 Third trifocal tensor matrix T_3
283 * @param normedEpipole2 Resulting (normalized) epipole in second view
284 * @param normedEpipole3 Resulting (normalized) epipole in third view
285 * @tparam tUseIF Calculation for inverted flipped camera system, if set
286 * @return True, if succeeded
287 */
288 template<bool tUseIF>
289 static bool epipoles(const Scalar* const trifocal1, const Scalar* const trifocal2, const Scalar* const trifocal3, Vector3& normedEpipole2, Vector3& normedEpipole3);
290
291 private:
292
293 /**
294 * Calculates the trifocal tensor using linear system.
295 * @param points1 Image points of first set
296 * @param points2 Image points of second set
297 * @param points3 Image points of third set
298 * @param correspondences Number of point correspondences (at least 7)
299 * @param trifocal3x9 Pointer to resulting values of trifocal tensor matrices
300 * @param matrixA Pointer to constructed linear system, if needed
301 * @return True, if succeeded
302 */
303 static bool trifocalTensorLinear(const ImagePoint* points1, const ImagePoint* points2, const ImagePoint* points3, const size_t correspondences, Scalar* trifocal3x9, Matrix* matrixA = nullptr);
304
305 /**
306 * The normalized linear algorithm of computation of trifocal tensor.
307 * Calculates the trifocal tensor by three sets of at least seven corresponding image points.
308 * @param points1 Image points of first set
309 * @param points2 Image points of second set
310 * @param points3 Image points of third set
311 * @param correspondences Number of point correspondences (at least 7)
312 * @param trifocal3x9 Pointer to resulting values of trifocal tensor matrices
313 * @param matrixA Pointer to constructed linear system, if needed
314 * @return True, if succeeded
315 */
316 static bool trifocalTensorNormalizedLinear(const ImagePoint* points1, const ImagePoint* points2, const ImagePoint* points3, const size_t correspondences, Scalar* trifocal3x9, Matrix* matrixA = nullptr);
317
318 /**
319 * Calculates the trifocal tensor error in point–point–point correspondence equation:
320 * [x_2]_x * (sum_i(x_1^i * T_i) * [x_3]_x).
321 * @param trifocal Trifocal tensor matrices
322 * @param points1 Image points of first set
323 * @param points2 Image points of second set
324 * @param points3 Image points of third set
325 * @param correspondences Number of point correspondences (at least 7)
326 * @param errorMatrix Resulting 3x3 error matrix is needed
327 * @return The absolute sum of 3x3 error matrix
328 */
329 static Scalar errorMatrix(const TrifocalTensor& trifocal, const ImagePoint* points1, const ImagePoint* points2, const ImagePoint* points3, const size_t correspondences, SquareMatrix3* errorMatrix = nullptr);
330
331 /**
332 * Calculates a transformation for a projective basis defined by four individual (image) target points each corresponding to a specific (projective/3D) reference points.<br>
333 * The following projective reference points are used: e_i = (1, 0, 0), (0, 1, 0), (0, 0, 1), (1, 1, 1).<br>
334 * The resulting transformation transforms the provided image points to projective references points:<br>
335 * si * ei = H * pi, each up to a scale factor si.
336 * @param imagePointForTargetPoint100 Image point p0 corresponding to s0 * (1, 0, 0)
337 * @param imagePointForTargetPoint010 Image point p1 corresponding to s1 * (0, 1, 0)
338 * @param imagePointForTargetPoint001 Image point p2 corresponding to s2 * (0, 0, 1)
339 * @param imagePointForTargetPoint111 Image point p3 corresponding to s3 * (1, 1, 1)
340 * @param baseTransformation Resulting transformation
341 * @return True, if succeeded
342 */
343 static bool calculateProjectiveBasisTransform(const Vector2& imagePointForTargetPoint100, const Vector2& imagePointForTargetPoint010, const Vector2& imagePointForTargetPoint001, const Vector2& imagePointForTargetPoint111, SquareMatrix3& baseTransformation);
344
345 /**
346 * Checks if a given 2D point is collinear to three given 2D points (defined by a 2D triangle).
347 * @param triangle The triangle defining the three points
348 * @param point The point to be check
349 * @param threshold Threshold of variance from linearity condition, with range (0, 1]
350 * @return True, if the given point is collinear to any of two corners of the triangle
351 */
352 static inline bool pointIsCollinear(const Triangle2& triangle, const Vector2& point, const Scalar threshold = Scalar(0.01));
353};
354
356{
357 // nothing to do here
358}
359
361{
362 tensorMatrices[0] = matrix0;
363 tensorMatrices[1] = matrix1;
364 tensorMatrices[2] = matrix2;
365}
366
368{
369 ocean_assert(matrices != nullptr);
370
371 tensorMatrices[0] = matrices[0];
372 tensorMatrices[1] = matrices[1];
373 tensorMatrices[2] = matrices[2];
374}
375
376inline const SquareMatrix3& MultipleViewGeometry::TrifocalTensor::operator[](const unsigned int index) const
377{
378 ocean_assert(index < 3u);
379 return tensorMatrices[index];
380}
381
383{
384 ocean_assert(index < 3u);
385 return tensorMatrices[index];
386}
387
389{
390 return tensorMatrices;
391}
392
394{
395 return tensorMatrices;
396}
397
398/**
399 * This class implements self-calibration for multiple views.
400 * @ingroup geometry
401 */
402class OCEAN_GEOMETRY_EXPORT AutoCalibration
403{
404 public:
405
406 /**
407 * Estimate the common intrinsic camera matrix based on an Absolute Conic omega (&omega;):<br>
408 * omega = K * K^T --- (&omega;_j = &omega; = KK^T).<br>
409 * Solve a linear system by assuming equal entities in each &omega;
410 * @param iFlippedProjectionMatrices The inverted and flipped camera projection matrices [K * P0], [K * P1], [K * P2], ..., with Pi = [Ri | ti], at least 3
411 * @param cameraIntrinsics Resulting intrinsic camera matrix
412 * @param Q Optional resulting absolute dual quadric Q&infin;
413 * @param omega Optional resulting absolute conic &omega
414 * @return True, if succeeded
415 * @see findAbsoluteDualQuadricLinear()
416 */
417 static bool findCommonIntrinsicsFromProjectionMatricesIF(const ConstIndexedAccessor<HomogenousMatrix4>& iFlippedProjectionMatrices, SquareMatrix3& cameraIntrinsics, SquareMatrix4* Q = nullptr, SquareMatrix3* omega = nullptr);
418
419 /**
420 * Estimate a common intrinsic camera matrix based on an Absolute Conic &omega;:<br>
421 * &omega;_j = &omega; = KK^T.<br>
422 * Solve a linear system by assuming zero skew, a known principle point (centered in the camera frame) and equal focal length for each &omega;
423 * @param iFlippedProjectionMatrices Inverted and flipped camera projection matrices [K | P0], [K | P1], [K | P2], ..., with Pi = [Ri | ti], at least 3
424 * @param imageWidth Width of the camera frame in pixel, with range [1, infinity)
425 * @param imageHeight Height of the camera frame in pixel, with range [1, infinity)
426 * @param cameraIntrinsics Resulting camera intrinsics matrix
427 * @param Q Resulting absolute dual quadric Q&infin;, optionally
428 * @param omega Resulting absolute conic &omega, optionally
429 * @return True, if succeeded
430 * @see findAbsoluteDualQuadricLinear()
431 */
432 static bool findCommonIntrinsicsFromProjectionMatricesIF(const ConstIndexedAccessor<HomogenousMatrix4>& iFlippedProjectionMatrices, const unsigned int imageWidth, const unsigned int imageHeight, SquareMatrix3& cameraIntrinsics, SquareMatrix4* Q = nullptr, SquareMatrix3* omega = nullptr);
433
434 /**
435 * Estimates the absolute dual quadric Q_infinity (Q&infin;) from several projection-pose matrices by solving a linear system:<br>
436 * omega = P_j * Q_infinity * P_j^T --- (&omega;_j = P_j * Q&infin; * P_j^T).<br>
437 * Here, we assume no skew and the principle point in the center of the camera frame.
438 * @param iFlippedProjectionMatrices The inverted and flipped camera projection matrices [K | P0], [K | P1], [K | P2], ..., with Pi = [Ri | ti], at least 3
439 * @param matrixQ Resulting absolute dual quadric Q_infinity --- (Q&infin;)
440 * @param imageWidth Width of the camera frame in pixel, with range [1, infinity)
441 * @param imageHeight Height of the camera frame in pixel, with range [1, infinity)
442 * @param equalFxFy Forces equal focal length in both dimension
443 * @return True, if succeeded
444 * @see findCommonIntrinsicsFromProjectionMatricesIF()
445 */
446 static bool determineAbsoluteDualQuadricLinearIF(const ConstIndexedAccessor<HomogenousMatrix4>& iFlippedProjectionMatrices, SquareMatrix4& matrixQ, const unsigned int imageWidth, const unsigned int imageHeight, bool equalFxFy = true);
447
448 /**
449 * Determines individual intrinsic camera matrices from a known absolute dual quadric Q_infinity (Q&infin;) and corresponding camera-projection-pose matrices:<br>
450 * omega_j = P_j * Q_infinity * P_J^T = K_j * K_j^T --- (&omega;_j = P_j * Q&infin; * P_J^T = K_j * K_j^T).<br>
451 * The Cholesky decomposition is applied to factorize omega into K.
452 * @param symmetricQ The absolute dual quadric q_infinity which is symmetric
453 * @param iFlippedProjectionMatrices The inverted and flipped camera projection pose matrices
454 * @param intrinsics The resulting intrinsic camera matrices, one for each projection pose matrix
455 * @return True, if succeeded
456 * @see findAbsoluteDualQuadricLinear()
457 * @see transformProjectionsZeroPrinciplePoint()
458 */
459 static bool intrinsicsFromAbsoluteDualQuadricIF(const SquareMatrix4& symmetricQ, const ConstIndexedAccessor<HomogenousMatrix4>& iFlippedProjectionMatrices, SquareMatrix3* intrinsics);
460
461 /**
462 * Transforms a projective reconstruction towards a metric reconstruction.<br>
463 * Q&infin; = H * Î * H^T.<br>
464 * P_metric = P * H.<br>
465 * @param Q Absolute dual quadric Q&infin;
466 * @param iFlippedProjectionMatrices The camera projection matrices (inverted flipped)
467 * @param iFlippedMetricProjectionMatrices Resulting metric projection matrices (inverted flipped)
468 * @param transformation Optional resulting perspective transformation matrix
469 * @return True, if succeeded
470 * @see getTransformProjectiveToMetricMatrix()
471 */
472 static bool transformProjectiveToMetricIF(const SquareMatrix4& Q, const ConstIndexedAccessor<HomogenousMatrix4>& iFlippedProjectionMatrices, HomogenousMatrix4* iFlippedMetricProjectionMatrices, SquareMatrix4* transformation = nullptr);
473
474 /**
475 * 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.
476 * Based on the following equation: P_metric = K * [R t] we can determine the camera poses by: [R t] = K^-1 * p_metric.
477 * @param metricProjectionsIF The inverted and flipped metric camera projection matrices
478 * @param intrinsic The already known intrinsic camera matrix K
479 * @param posesIF The resulting inverted and flipped camera poses, one for each given camera projection matrix
480 * @return True, if succeeded
481 * @see transformProjectiveToMetric().
482 */
483 static bool metricProjectionMatricesToPosesIF(const ConstIndexedAccessor<HomogenousMatrix4>& metricProjectionsIF, const SquareMatrix3& intrinsic, HomogenousMatrix4* posesIF);
484
485 protected:
486
487 /**
488 * 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.<br>
489 * P' = T * P.
490 * @param iFlippedProjectionMatrices Inverted and flipped camera projection matrices, at least one
491 * @param imageWidth Width of image in pixel, with range [1, infinity)
492 * @param imageHeight Height of image in pixel, with range [1, infinity)
493 * @param iFlippedNormalizedProjectionMatrices Resulting normalized inverted and flipped camera projection matrices, one for each given camera projection matrix
494 * @param backTransformation Optional resulting back transformation matrix T^-1
495 * @return True, if succeeded
496 * @see transformProjectiveToMetric()
497 */
498 static bool transformProjectionsZeroPrinciplePoint(const ConstIndexedAccessor<HomogenousMatrix4>& iFlippedProjectionMatrices, const unsigned int imageWidth, const unsigned int imageHeight, HomogenousMatrix4* iFlippedNormalizedProjectionMatrices, SquareMatrix3* backTransformation = nullptr);
499
500 /**
501 * Determines the perspective transformation to get a metric reconstruction.<br>
502 * Q&infin; = H * Î * H^T, factorized by eigen decomposition.
503 * @param Q Absolute dual quadric Q&infin;
504 * @param transformation Resulting perspective transformation H
505 * @return True, if succeeded
506 * @see transformProjectiveToMetric()
507 */
509
510 private:
511
512 /**
513 * Performs the decomposition of an absolute conic omega (&omega;) into the intrinsic camera matrix:<br>
514 * omega = K * K^T --- (&omega; = K * K^T), where K is the camera matrix (which is a upper triangular matrix).<br>
515 * The Cholesky decomposition is applied.
516 * @param omega The (symmetric) absolute conic to be decomposed (&omega;)
517 * @param cameraIntrinsic The resulting intrinsic camera matrix
518 * @return True, if succeeded
519 */
520 static bool upperTriangleCholeskyDecomposition(const SquareMatrix3& omega, SquareMatrix3& cameraIntrinsic);
521
522 /**
523 * Creates a line for the linear system for the zero condition of absolute conic &omega;(i, j).<br>
524 * The line contains values of the upper triangle entities of absolute dual quadric matrix Q_infinity --- (Q&infin;):
525 * &omega;(i, j) = [P * Q&infin; * P^T](i, j) = 0
526 * @param omegaRowIndex Row index of absolute conic &omega;
527 * @param omegaColumnIndex Column index of absolute conic &omega;
528 * @param iFlippedProjectionMatrix The inverted and flipped camera projection matrix, must be valid
529 * @return A line matrix [1x10] containing the values of the upper triangle entities of the symmetric matrix Q&infin;
530 */
531 static Matrix createLinearSystemForAbsoluteDualQuadric(const unsigned int omegaRowIndex, const unsigned int omegaColumnIndex, const HomogenousMatrix4& iFlippedProjectionMatrix);
532};
533
534inline bool MultipleViewGeometry::pointIsCollinear(const Triangle2& triangle2d, const Vector2& point, const Scalar threshold)
535{
536 ocean_assert(triangle2d.isValid() && threshold > 0);
537
538 const Vector3 barycenter = triangle2d.cartesian2barycentric(point);
539 return Numeric::isBelow(Numeric::abs(barycenter.x()), threshold) || Numeric::isBelow(Numeric::abs(barycenter.y()), threshold) || Numeric::isBelow(Numeric::abs(barycenter.z()), threshold);
540}
541
542}
543
544}
545
546#endif // META_OCEAN_GEOMETRY_MULTIPLE_VIEW_GEOMETRY_H
This class implements a base class for all indexed-based accessors allowing a constant reference acce...
Definition Accessor.h:241
This class implements self-calibration for multiple views.
Definition MultipleViewGeometry.h:403
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 transformProjectionsZeroPrinciplePoint(const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, const unsigned int imageWidth, const unsigned int imageHeight, HomogenousMatrix4 *iFlippedNormalizedProjectionMatrices, SquareMatrix3 *backTransformation=nullptr)
Transforms an inverted and flipped camera projection matrix P = K * [R|t] in a way that the principle...
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 — ...
static bool getTransformProjectiveToMetricMatrix(const SquareMatrix4 &Q, SquareMatrix4 &transformation)
Determines the perspective transformation to get a metric reconstruction.
static bool upperTriangleCholeskyDecomposition(const SquareMatrix3 &omega, SquareMatrix3 &cameraIntrinsic)
Performs the decomposition of an absolute conic omega (ω) into the intrinsic camera matrix: omega = ...
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 intrinsicsFromAbsoluteDualQuadricIF(const SquareMatrix4 &symmetricQ, const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, SquareMatrix3 *intrinsics)
Determines individual intrinsic camera matrices from a known absolute dual quadric Q_infinity (Q∞) an...
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 ...
static Matrix createLinearSystemForAbsoluteDualQuadric(const unsigned int omegaRowIndex, const unsigned int omegaColumnIndex, const HomogenousMatrix4 &iFlippedProjectionMatrix)
Creates a line for the linear system for the zero condition of absolute conic ω(i,...
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 (int...
Definition of a trifocal tensor matrix.
Definition MultipleViewGeometry.h:40
const SquareMatrix3 * operator()() const
Data operator returning the pointer to the first matrix of this tensor.
Definition MultipleViewGeometry.h:388
const SquareMatrix3 & operator[](const unsigned int index) const
Element operator.
Definition MultipleViewGeometry.h:376
TrifocalTensor()
Creates a new tensor object without initialization.
Definition MultipleViewGeometry.h:355
This class implements epipolar geometry functions for multiple views.
Definition MultipleViewGeometry.h:33
static bool epipolesIF(const TrifocalTensor &trifocal, Vector3 &iFlippedNormedEpipole2, Vector3 &iFlippedNormedEpipole3)
Calculates the normalized epipoles of second and third view from trifocal tensor for inverted flipped...
static bool trifocalTensorMinimizingError(const ImagePoint *points1, const ImagePoint *points2, const ImagePoint *points3, const size_t correspondences, TrifocalTensor &trifocal)
Computing a geometric valid trifocal tensor minimizing algebraic error.
static bool calibrateFromProjectionsMatricesIF(const ConstIndexedAccessor< HomogenousMatrix4 > &iFlippedProjectionMatrices, const unsigned int imageWidth, const unsigned int imageHeight, SquareMatrix3 &cameraIntrinsic, HomogenousMatrix4 *iFlippedPoses)
Calibrate multiple projection matrices from a single camera.
static bool calculateProjectiveBasisTransform(const Vector2 &imagePointForTargetPoint100, const Vector2 &imagePointForTargetPoint010, const Vector2 &imagePointForTargetPoint001, const Vector2 &imagePointForTargetPoint111, SquareMatrix3 &baseTransformation)
Calculates a transformation for a projective basis defined by four individual (image) target points e...
static bool projectiveReconstructionFrom6PointsIF(const ImagePoint *points1, const ImagePoint *points2, const ImagePoint *points3, const size_t correspondences, HomogenousMatrix4 &iFlippedProjectionMatrix1, HomogenousMatrix4 &iFlippedProjectionMatrix2, HomogenousMatrix4 &iFlippedProjectionMatrix3, const Scalar squaredSuccessThreshold=(2.5 *2.5), Scalar *squaredProjectionError=nullptr)
Computes geometric valid camera projection matrices which are determined up to a common 3d projection...
static bool trifocalTensorLinear(const ImagePoint *points1, const ImagePoint *points2, const ImagePoint *points3, const size_t correspondences, Scalar *trifocal3x9, Matrix *matrixA=nullptr)
Calculates the trifocal tensor using linear system.
static Scalar errorMatrix(const TrifocalTensor &trifocal, const ImagePoint *points1, const ImagePoint *points2, const ImagePoint *points3, const size_t correspondences, SquareMatrix3 *errorMatrix=nullptr)
Calculates the trifocal tensor error in point–point–point correspondence equation: [x_2]_x * (sum_i(x...
static bool fundamentalMatricesIF(const TrifocalTensor &trifocal, const Vector3 &iFlippedEpipole2, const Vector3 &iFlippedEpipole3, SquareMatrix3 &fundamental21, SquareMatrix3 &fundamental31)
Calculates the fundamental matrices of second view and third view from trifocal tensor.
static bool epipoles(const Scalar *const trifocal1, const Scalar *const trifocal2, const Scalar *const trifocal3, Vector3 &normedEpipole2, Vector3 &normedEpipole3)
Calculates the normalized epipoles of second and third view from trifocal tensor.
static bool cameraProjectionMatricesIF(const TrifocalTensor &trifocal, const Vector3 &iFlippedNormedEpipole2, const Vector3 &iFlippedNormedEpipole3, HomogenousMatrix4 &iFlippedProjectionMatrix2, HomogenousMatrix4 &iFlippedProjectionMatrix3)
Calculates the camera projection matrices of second and third view.
static bool projectiveReconstructionFrom6PointsIF(const ConstIndexedAccessor< ImagePoints > &imagePointsPerPose, NonconstIndexedAccessor< HomogenousMatrix4 > *posesIF, const Scalar squaredSuccessThreshold=Scalar(2.5 *2.5), Scalar *squaredProjectionError=nullptr)
Computes geometric valid camera projection matrices which are determined up to a common 3d projection...
static bool trifocalTensorFromProjectionMatrices(const HomogenousMatrix4 &iFlippedProjectionMatrixA, const HomogenousMatrix4 &iFlippedProjectionMatrixB, const HomogenousMatrix4 &iFlippedProjectionMatrixC, TrifocalTensor &trifocal)
Calculates the trifocal tensor by three projection matrix given: P_1 = [A | a4], P_2 = [B | b4],...
static bool trifocalTensorNormalizedLinear(const ImagePoint *points1, const ImagePoint *points2, const ImagePoint *points3, const size_t correspondences, TrifocalTensor &trifocal)
The normalized linear algorithm of computation of trifocal tensor.
static bool pointIsCollinear(const Triangle2 &triangle, const Vector2 &point, const Scalar threshold=Scalar(0.01))
Checks if a given 2D point is collinear to three given 2D points (defined by a 2D triangle).
Definition MultipleViewGeometry.h:534
static bool trifocalTensorIF(const ImagePoint *points1, const ImagePoint *points2, const ImagePoint *points3, const size_t correspondences, HomogenousMatrix4 &iFlippedProjectionMatrix1, HomogenousMatrix4 &iFlippedProjectionMatrix2, HomogenousMatrix4 &iFlippedProjectionMatrix3, TrifocalTensor *trifocalTensor=nullptr)
The normalized linear algorithm of computation of trifocal tensor.
static bool epipoles(const TrifocalTensor &trifocal, Vector3 &normedEpipole2, Vector3 &normedEpipole3)
Calculates the normalized epipoles of second and third view from trifocal tensor.
static bool trifocalTensorNormalizedLinear(const ImagePoint *points1, const ImagePoint *points2, const ImagePoint *points3, const size_t correspondences, Scalar *trifocal3x9, Matrix *matrixA=nullptr)
The normalized linear algorithm of computation of trifocal tensor.
static bool calibrateFromProjectionsMatricesIF(const HomogenousMatrix4 &iFlippedProjectionMatrix1, const HomogenousMatrix4 &iFlippedProjectionMatrix2, const HomogenousMatrix4 &iFlippedProjectionMatrix3, const unsigned int imageWidth, const unsigned int imageHeight, SquareMatrix3 &cameraIntrinsics, HomogenousMatrix4 &iFlippedPose1, HomogenousMatrix4 &iFlippedPose2, HomogenousMatrix4 &iFlippedPose3)
Calibrate three projection matrices from a single camera.
static bool trifocalTensorFromProjectionMatrices(const HomogenousMatrix4 &iFlippedProjectionMatrixB, const HomogenousMatrix4 &iFlippedProjectionMatrixC, TrifocalTensor &trifocal)
Calculates the trifocal tensor by two projection matrix given: P_1 = [I | 0], P_2 = [A | a4],...
This class implements a base class for all indexed-based accessors allowing a non-constant reference ...
Definition Accessor.h:284
static T abs(const T value)
Returns the absolute value of a given value.
Definition Numeric.h:1220
static constexpr bool isBelow(const T value, const T upper, const T epsilon=NumericT< T >::eps())
Returns whether a parameter lies on or below a given border tolerating a small epsilon.
Definition Numeric.h:2927
This class implements a 2D triangle with Cartesian coordinates.
Definition Triangle2.h:81
VectorT3< T > cartesian2barycentric(const VectorT2< T > &cartesian) const
Returns the barycentric coordinate of a given 2D Cartesian coordinate defined in relation to this tri...
Definition Triangle2.h:767
bool isValid() const
Returns whether this triangle can provide valid barycentric coordinates (for 64 bit floating point va...
Definition Triangle2.h:806
const T & y() const noexcept
Returns the y value.
Definition Vector3.h:824
const T & x() const noexcept
Returns the x value.
Definition Vector3.h:812
const T & z() const noexcept
Returns the z value.
Definition Vector3.h:836
float Scalar
Definition of a scalar type.
Definition Math.h:129
The namespace covering the entire Ocean framework.
Definition Accessor.h:15