Ocean
geometry/Utilities.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_UTILITIES_H
9 #define META_OCEAN_GEOMETRY_UTILITIES_H
10 
12 
13 #include "ocean/base/Accessor.h"
14 #include "ocean/base/Median.h"
15 
16 #include "ocean/math/AnyCamera.h"
17 #include "ocean/math/Cone3.h"
18 #include "ocean/math/Cylinder3.h"
22 #include "ocean/math/Plane3.h"
24 
25 namespace Ocean
26 {
27 
28 namespace Geometry
29 {
30 
31 /**
32  * This class implements utilities function for the tracking library.
33  * @ingroup geometry
34  */
35 class OCEAN_GEOMETRY_EXPORT Utilities
36 {
37  public:
38 
39  /**
40  * Projects one image points onto a 3D plane and returns the resulting 3D object point.
41  * Beware: The back projected point may be located behind the camera due to the position and orientation of the given plane!<br>
42  * Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.<br>
43  * @param pinholeCamera The pinhole camera object
44  * @param pose Pose of the camera
45  * @param plane 3D plane that is used to determine the position of the back-projected 3D object point
46  * @param imagePoint Image point that will be back-projected
47  * @param useDistortionParameters True, to use the distortion parameters of the camera
48  * @param frontObjectPoint Optional resulting statement whether the resulting object point is located in front of the camera; True, if so
49  * @return Resulting 3D object point
50  */
51  static ObjectPoint backProjectImagePoint(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const Plane3& plane, const ImagePoint& imagePoint, const bool useDistortionParameters, bool* frontObjectPoint = nullptr);
52 
53  /**
54  * Projects a set of given image points onto a 3D plane and returns the resulting 3D object points.
55  * Beware: The back projected points may be located behind the camera due to the position and orientation of the given plane!<br>
56  * Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.
57  * @param anyCamera The camera profile defining the projection and distortion
58  * @param world_T_camera The transformation from the camera coordinate system to world coordinates, `worldPoint = world_T_camera * cameraPoint`, must be valid
59  * @param plane 3D plane that is used to determine the position of the back-projected 3D object points
60  * @param imagePoints Image points that will be back-projected
61  * @param numberImagePoints Number of given image points
62  * @param frontObjectPointIndices Optional resulting indices of all object points lying in front of the camera
63  * @return Resulting 3D object points
64  * @see backProjectImagePointsDamped().
65  */
66  static ObjectPoints backProjectImagePoints(const AnyCamera& anyCamera, const HomogenousMatrix4& world_T_camera, const Plane3& plane, const ImagePoint* imagePoints, const size_t numberImagePoints, Indices32* frontObjectPointIndices = nullptr);
67 
68  /**
69  * Deprecated.
70  *
71  * Projects a set of given image points onto a 3D plane and returns the resulting 3D object points.
72  * Optional camera distortion will be clamped at the border of the camera's frame.<br>
73  * Beware: The back projected points may be located behind the camera due to the position and orientation of the given plane!<br>
74  * Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.
75  * @param pinholeCamera The pinhole camera profile defining the projection and optional distortion
76  * @param pose Pose of the camera
77  * @param plane 3D plane that is used to determine the position of the back-projected 3D object points
78  * @param imagePoints Image points that will be back-projected
79  * @param numberImagePoints Number of given image points
80  * @param useDistortionParameters True, to use the distortion parameters of the camera
81  * @param frontObjectPointIndices Optional resulting indices of all object points lying in front of the camera
82  * @return Resulting 3D object points
83  * @see backProjectImagePointsDamped().
84  */
85  static ObjectPoints backProjectImagePoints(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const Plane3& plane, const ImagePoint* imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32* frontObjectPointIndices = nullptr);
86 
87  /**
88  * Projects a set of given image points onto a 3D cylinder and returns *only* the resulting 3D object points for rays that intersect the cylinder.
89  * @param anyCamera The camera profile defining the projection and distortion
90  * @param world_T_camera The transformation from the camera coordinate system to world coordinates, `worldPoint = world_T_camera * cameraPoint`, must be valid
91  * @param cylinder 3D cylinder that is used to determine the position of the back-projected 3D object points
92  * @param imagePoints Image points that will be back-projected
93  * @param numberImagePoints Number of given image points
94  * @param intersectingPointIndices Output indices of all 2D points whose rays actually intersect with the cylinder
95  * @return Resulting 3D object points
96  */
97  static ObjectPoints backProjectImagePoints(const AnyCamera& anyCamera, const HomogenousMatrix4& world_T_camera, const Cylinder3& cylinder, const ImagePoint* imagePoints, const size_t numberImagePoints, Indices32& intersectingPointIndices);
98 
99  /**
100  * Deprecated.
101  *
102  * Projects a set of given image points onto a 3D cylinder and returns *only* the resulting 3D object points for rays that intersect the cylinder.
103  * Optional camera distortion will be clamped at the border of the camera's frame.<br>
104  * @param pinholeCamera The pinhole camera profile defining the projection and optional distortion
105  * @param pose Pose of the camera
106  * @param cylinder 3D cylinder that is used to determine the position of the back-projected 3D object points
107  * @param imagePoints Image points that will be back-projected
108  * @param numberImagePoints Number of given image points
109  * @param useDistortionParameters True, to use the distortion parameters of the camera
110  * @param intersectingPointIndices Output indices of all 2D points whose rays actually intersect with the cylinder
111  * @return Resulting 3D object points
112  */
113  static ObjectPoints backProjectImagePoints(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const Cylinder3& cylinder, const ImagePoint* imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32& intersectingPointIndices);
114 
115  /**
116  * Projects a set of given image points onto a 3D cone and returns *only* the resulting 3D object points for rays that intersect the cone.
117  * @param anyCamera The camera profile defining the projection and distortion
118  * @param world_T_camera The transformation from the camera coordinate system to world coordinates, `worldPoint = world_T_camera * cameraPoint`, must be valid
119  * @param cone 3D cone that is used to determine the position of the back-projected 3D object points
120  * @param imagePoints Image points that will be back-projected
121  * @param numberImagePoints Number of given image points
122  * @param intersectingPointIndices Output indices of all 2D points whose rays actually intersect with the cone
123  * @return Resulting 3D object points
124  */
125  static ObjectPoints backProjectImagePoints(const AnyCamera& anyCamera, const HomogenousMatrix4& world_T_camera, const Cone3& cone, const ImagePoint* imagePoints, const size_t numberImagePoints, Indices32& intersectingPointIndices);
126 
127  /**
128  * Deprecated.
129  *
130  * Projects a set of given image points onto a 3D cone and returns *only* the resulting 3D object points for rays that intersect the cone.
131  * Optional camera distortion will be clamped at the border of the camera's frame.<br>
132  * @param pinholeCamera The pinhole camera profile defining the projection and optional distortion
133  * @param pose Pose of the camera
134  * @param cone 3D cone that is used to determine the position of the back-projected 3D object points
135  * @param imagePoints Image points that will be back-projected
136  * @param numberImagePoints Number of given image points
137  * @param useDistortionParameters True, to use the distortion parameters of the camera
138  * @param intersectingPointIndices Output indices of all 2D points whose rays actually intersect with the cone
139  * @return Resulting 3D object points
140  */
141  static ObjectPoints backProjectImagePoints(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const Cone3& cone, const ImagePoint* imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32& intersectingPointIndices);
142 
143  /**
144  * Projects a set of given image points onto a 3D plane and returns the resulting 3D object points.
145  * Optional camera distortion will be damped outside the border of the camera's frame.<br>
146  * Beware: The back projected points may be located behind the camera due to the position and orientation of the given plane!<br>
147  * Beware: Ensure that the given plane is not parallel with the viewing direction of the camera.
148  * @param pinholeCamera The pinhole camera profile defining the projection and optional distortion
149  * @param pose Pose of the camera
150  * @param plane 3D plane that is used to determine the position of the back-projected 3D object points
151  * @param imagePoints Image points that will be back-projected
152  * @param numberImagePoints Number of given image points
153  * @param useDistortionParameters True, to use the distortion parameters of the camera
154  * @param frontObjectPointIndices Optional resulting indices of all object points lying in front of the camera
155  * @return Resulting 3D object points
156  * @see backProjectImagePoints().
157  */
158  static ObjectPoints backProjectImagePointsDamped(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const Plane3& plane, const ImagePoint* imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32* frontObjectPointIndices = nullptr);
159 
160  /**
161  * Creates a set of 3D object points for a set of given 2D image points.
162  * The 3D object points will lie on the ray which intersects the individual image points and the camera's center of projection.<br>
163  * The distance between 3D object points and the camera's center of projection defines the locations of the object points.
164  * @param camera The camera profile defining the projection, must be valid
165  * @param world_T_camera The pose of the camera, with default camera pointing towards the negative z-space with y-axis upwards, must be valid
166  * @param imagePoints Image points that will be back-projected, at least one
167  * @param distance The distance between the camera's center of project and the resulting object points, with range (0, infinity)
168  * @return The resulting 3D object points, defined in world
169  */
170  static Vectors3 createObjectPoints(const AnyCamera& camera, const HomogenousMatrix4& world_T_camera, const ConstIndexedAccessor<Vector2>& imagePoints, const Scalar distance);
171 
172  /**
173  * Deprecated.
174  *
175  * Creates a set of 3D object points by a set of given 2D image points.
176  * The 3D object points are lying on the ray which intersect the individual image points and the camera's center of projection.<br>
177  * The distance between 3D object points and the camera's center of projection defines the locations of the object points.<br>
178  * @param pinholeCamera The pinhole camera profile defining the projection, must be valid
179  * @param pose Pose of the camera, must be valid
180  * @param imagePoints Image points that will be back-projected
181  * @param useDistortionParameters True, to use the distortion parameters of the camera
182  * @param distance The distance between the camera's center of project and the resulting object points, should be in range (0, infinity)
183  * @return Resulting 3D object points
184  */
185  static ObjectPoints createObjectPoints(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const ConstIndexedAccessor<ImagePoint>& imagePoints, const bool useDistortionParameters, const Scalar distance);
186 
187  /**
188  * Determines 3D object points by triangulating two sets of 2D image points from different camera poses.
189  * @param camera0 The camera profile of the first camera, must be valid
190  * @param camera1 The camera profile of the second camera, must be valid
191  * @param world_T_camera0 The camera pose of the first camera, with default camera pointing towards the negative z-space with y-axis upwards, must be valid
192  * @param world_T_camera1 The camera pose of the second camera, with default camera pointing towards the negative z-space with y-axis upwards, must be valid
193  * @param imagePoints0 The 2D image points located in the first camera
194  * @param imagePoints1 The 2D image points located in the second camera, each point must have a corresponding point in the first camera
195  * @param objectPoints The resulting valid 3D object points, does not provide invalid object points
196  * @param validIndices The resulting indices of the valid point correspondences for which a 3D object points could be determined, one index of reach resulting 3D object point
197  * @param onlyFrontPoints True, if only front object points are determined
198  * @param maximalSqrError The maximal squared projection pixel error for valid object points
199  */
200  static void triangulateObjectPoints(const AnyCamera& camera0, const AnyCamera& camera1, const HomogenousMatrix4& world_T_camera0, const HomogenousMatrix4& world_T_camera1, const ConstIndexedAccessor<Vector2>& imagePoints0, const ConstIndexedAccessor<Vector2>& imagePoints1, Vectors3& objectPoints, Indices32& validIndices, const bool onlyFrontPoints = true, const Scalar maximalSqrError = Scalar(3 * 3));
201 
202  /**
203  * Projects a set of given 2D image triangles onto a 3D plane and returns the resulting 3D object triangles.
204  * @param pinholeCamera The pinhole camera object
205  * @param pose Pose of the camera
206  * @param plane 3D plane that is used to determine the position of the back-projected 3D object points
207  * @param triangles Triangles that will be back-projected
208  * @param numberTriangles Number of given image points
209  * @param useDistortionParameters True, to use the distortion parameters of the camera
210  * @return Resulting 3D triangles
211  */
212  static Triangles3 backProjectTriangles(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const Plane3& plane, const Triangle2* triangles, const size_t numberTriangles, const bool useDistortionParameters);
213 
214  /**
215  * Counts the number of object points that are in front of a given camera.
216  * @param pinholeCamera The pinhole camera profile to be used
217  * @param pose Pose of the camera (extrinsic camera matrix with viewing direction along the negative z-axis)
218  * @param objectPoints Object points for which the number of front object points will be determined
219  * @param numberObjectPoints The number of provided object points
220  * @return Number of object points located in front of the camera
221  * @see countFrontObjectPointsIF().
222  */
223  static inline size_t countFrontObjectPoints(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const ObjectPoint* objectPoints, const size_t numberObjectPoints);
224 
225  /**
226  * Counts the number of object points that are in front of a given camera.
227  * @param pinholeCamera The pinhole camera profile to be used
228  * @param invertedFlippedPose Inverted and flipped pose of the camera (not the default extrinsic camera matrix)
229  * @param objectPoints Object points for which the number of front object points will be determined
230  * @param numberObjectPoints The number of provided object points
231  * @return Number of object points located in front of the camera
232  * @see countFrontObjectPoints().
233  */
234  static size_t countFrontObjectPointsIF(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& invertedFlippedPose, const ObjectPoint* objectPoints, const size_t numberObjectPoints);
235 
236  /**
237  * Counts the number of object points that are visible in two individual camera frames and are located in front of both cameras.
238  * @param cameraFirst The camera profile of the first frame, optional distortion parameters of the camera will not be considered
239  * @param cameraSecond The camera profile of the first frame, optional distortion parameters of the camera will not be considered
240  * @param poseFirst Pose of the first camera
241  * @param poseSecond Pose of the second camera
242  * @param imagePointsFirst Image points located in the first frame
243  * @param imagePointsSecond Image points located in the second frame, each point corresponds to one point in the first frame (correspondence is defined by index)
244  * @param correspondences Number of given image point correspondences
245  * @return Number of image points located in front of both camera
246  */
247  static size_t countFrontObjectPoints(const PinholeCamera& cameraFirst, const PinholeCamera& cameraSecond, const HomogenousMatrix4& poseFirst, const HomogenousMatrix4& poseSecond, const ImagePoint* imagePointsFirst, const ImagePoint* imagePointsSecond, const size_t correspondences);
248 
249  /**
250  * Creates the covariance matrix for a given set of image points.
251  * @param imagePoints Image points for that the covariance will be determined
252  * @param number Number of image points
253  * @param minimalSigma Defining the minimal sigma that is applied, with range [0, infinity)
254  * @return Resulting covariance matrix
255  */
256  static inline SquareMatrix2 covarianceMatrix(const ImagePoint* imagePoints, const size_t number, const Scalar minimalSigma = 0);
257 
258  /**
259  * Creates the covariance matrix for a given set of image points.
260  * @param imagePoints Image points for that the covariance will be determined
261  * @param number Number of image points
262  * @param meanPoint Already determined mean point of the provided image points
263  * @param minimalSigma Defining the minimal sigma that is applied, with range [0, infinity)
264  * @return Resulting covariance matrix
265  */
266  static SquareMatrix2 covarianceMatrix(const ImagePoint* imagePoints, const size_t number, const ImagePoint& meanPoint, const Scalar minimalSigma = 0);
267 
268  /**
269  * Creates the covariance matrix for a given set of image points.
270  * @param imagePoints Image points for that the covariance will be determined
271  * @param indices A set of indices that define a subset of the entire image points
272  * @param numberIndices Number of provided indices
273  * @param minimalSigma Defining the minimal sigma that is applied, with range [0, infinity)
274  * @param meanPoint Resulting mean point of the filtered image points
275  * @return Resulting covariance matrix
276  */
277  static SquareMatrix2 covarianceMatrix(const ImagePoint* imagePoints, const unsigned int* indices, const size_t numberIndices, const Scalar minimalSigma, ImagePoint& meanPoint);
278 
279  /**
280  * Creates a covariance matrix by two given orthogonal vectors.
281  * @param direction0 Direction of the major axis, with unit length
282  * @param sigma0 Standard deviation of the major axis (equivalent to the square root of the first eigenvalue of the covariance matrix)
283  * @param direction1 Direction of the minor axis, perpendicular to the main direction, with unit length
284  * @param sigma1 Standard deviation of the second direction (equivalent to the square root of the second eigenvalue of the covariance matrix)
285  * @return Resulting covariance matrix
286  */
287  static SquareMatrix2 covarianceMatrix(const Vector2& direction0, const Scalar sigma0, const Vector2& direction1, const Scalar sigma1);
288 
289  /**
290  * Creates a covariance matrix by two given orthogonal vectors.
291  * @param direction0 Direction of the major axis, with standard deviation as length
292  * @param direction1 Direction of the minor axis, perpendicular to the main direction, with standard deviation as length
293  * @return Resulting covariance matrix
294  */
295  static SquareMatrix2 covarianceMatrix(const Vector2& direction0, const Vector2& direction1);
296 
297  /**
298  * Creates a covariance matrix by one given vector representing the major axis.
299  * @param majorDirection Direction of the major axis with standard deviation as length
300  * @param minimalSigma Minimal sigma that will be used (will be used if the length of the major direction is too small)
301  * @param minorFactor Ratio between the sigma of the minor and the major sigma, with range (0, 1]
302  * @return Resulting covariance matrix
303  */
304  static SquareMatrix2 covarianceMatrix(const Vector2& majorDirection, const Scalar minimalSigma = 1, const Scalar minorFactor = Scalar(0.01));
305 
306  /**
307  * Decomposes a covariance matrix.
308  * @param covarianceMatrix Covariance matrix that has to be decomposed
309  * @param direction0 Resulting major axis, with standard deviation as length (the square root of the first Eigen value)
310  * @param direction1 Resulting minor axis, with standard deviation as length (the square root of the second Eigen value)
311  * @return True, if succeeded
312  */
313  static bool decomposeCovarianceMatrix(const SquareMatrix2& covarianceMatrix, Vector2& direction0, Vector2& direction1);
314 
315  /**
316  * Returns whether a polygon of given 2D points is convex.
317  * A polygon consisting of 0 to 2 vertices is considered to be convex.
318  * @param vertices The vertices of the polygon, can be nullptr if size == 0
319  * @param size Number of vertices in the polygon, range: [0, infinity)
320  * @param strict If true, the polygon is tested for strict convexity (i.e. every internal angle is less than 180 degrees), otherwise internal angles can be up equal to 180 degrees
321  * @return True if the polygon is convex, otherwise false
322  */
323  static bool isPolygonConvex(const Vector2* vertices, const size_t size, const bool strict = true);
324 
325  /**
326  * Compute the area of a polygon
327  * @param vertices The vertices of a polygon (can be convex or concave but must not be self-intersecting)
328  * @param size Number of vertices in the polygon, range: [0, infinity)
329  * @return The absolute value of the area of the polygon (this value is undefined if the polygon is self-intersecting), range: [0, infinity)
330  */
331  static inline Scalar computePolygonArea(const Vector2* vertices, size_t size);
332 
333  /**
334  * Compute the area of a polygon
335  * @param vertices The vertices of a polygon (can be convex or concave but must not be self-intersecting)
336  * @return The absolute value of the area of the polygon (this value is undefined if the polygon is self-intersecting), range: [0, infinity)
337  * @sa CV::Segmentation::PixelContour::area()
338  */
339  static inline Scalar computePolygonArea(const Vectors2& vertices);
340 
341  /**
342  * Compute the signed area of a polygon
343  * The value of the area will be positive if the vertices are in counter-clockwise order and negative if they are in clock-wise order.
344  * @param vertices The vertices of a polygon (can be convex or concave but must not be self-intersecting)
345  * @param size Number of vertices in the polygon, range: [0, infinity)
346  * @return The area of the polygon (this value is undefined if the polygon is self-intersecting), range: (-infinity, infinity)
347  * @sa CV::Segmentation::PixelContour::areaSigned()
348  */
349  static Scalar computePolygonAreaSigned(const Vector2* vertices, size_t size);
350 
351  /**
352  * Compute the signed area of a polygon
353  * The value of the area will be positive if the vertices are in counter-clockwise order and negative if they are in clock-wise order.
354  * @param vertices The vertices of a polygon (can be convex or concave but must not be self-intersecting)
355  * @return The area of the polygon (this value is undefined if the polygon is self-intersecting), range: (-infinity, infinity)
356  */
357  static inline Scalar computePolygonAreaSigned(const Vectors2& vertices);
358 
359  /**
360  * Returns whether a given point lies inside a convex polygon.
361  * For polygons consisting of less than 3 points, this function always returns false.
362  * A point located on an edge of the polygon is considered as inside the polygon.
363  * @param vertices The vertices of a convex polygon, can be nullptr if size == 0
364  * @param size The number of vertices in the polygon, range: [0, infinity)
365  * @param point The point to be tested
366  * @return True, if the point is inside the polygon, otherwise false
367  */
368  static bool isInsideConvexPolygon(const Vector2* vertices, size_t size, const Vector2& point);
369 
370  /**
371  * Returns whether a given point lies inside a convex polygon.
372  * For polygons consisting of less than 3 points, this function always returns false.
373  * A point located on an edge of the polygon is considered as inside the polygon.
374  * @param vertices The vertices of a convex polygon, can be nullptr if size == 0
375  * @param point The point to be tested
376  * @return True, if the point is inside the polygon, otherwise false
377  */
378  static inline bool isInsideConvexPolygon(const Vectors2& vertices, const Vector2& point);
379 
380  /**
381  * Computation of the intersection of two convex polygons
382  * @param vertices0 The vertices of the first polygon
383  * @param size0 The number of vertices in the first polygon, range: [3, infinity)
384  * @param vertices1 The vertices of the second polygon
385  * @param size1 The number of vertices of the second polygon, range: [3, infinity)
386  * @param intersectedPolygon The resulting intersection represented as a polygon
387  * @return True, if succeeded
388  */
389  static bool intersectConvexPolygons(const Vector2* vertices0, const size_t size0, const Vector2* vertices1, const size_t size1, Vectors2& intersectedPolygon);
390 
391  /**
392  * Computation of the intersection of two convex polygons
393  * @param vertices0 The vertices of the first polygon, size: [3, infinity)
394  * @param vertices1 The vertices of the second polygon, size: [3, infinity)
395  * @param intersectedPolygon The resulting intersection represented as a polygon
396  * @return True, if succeeded
397  */
398  static inline bool intersectConvexPolygons(const Vectors2& vertices0, const Vectors2& vertices1, Vectors2& intersectedPolygon);
399 
400  /**
401  * Returns the mean position of a set of given 2D points.
402  * @param imagePointAccessor The accessor providing the image points, at least one
403  * @return The resulting mean position
404  * @tparam TAccessor The data type of the accessor providing the image points
405  */
406  template <typename TAccessor>
407  static inline ImagePoint meanImagePoint(const TAccessor& imagePointAccessor);
408 
409  /**
410  * Returns the mean position of a set of given 3D points.
411  * @param objectPointAccessor The accessor for the object points, at least one
412  * @return The resulting median position
413  * @tparam TAccessor The data type of the accessor providing the object points
414  */
415  template <typename TAccessor>
416  static inline ObjectPoint meanObjectPoint(const TAccessor& objectPointAccessor);
417 
418  /**
419  * Returns the median position of a set of given 2D points.
420  * The resulting position is determined by a component-wise median determination.
421  * @param imagePointAccessor The accessor for the image points, at least one
422  * @return The resulting median position
423  * @tparam TAccessor The data type of the accessor providing the object points
424  */
425  template <typename TAccessor>
426  static inline ImagePoint medianImagePoint(const TAccessor& imagePointAccessor);
427 
428  /**
429  * Returns the median position of a set of given 3D points.
430  * The resulting position is determined by a component-wise median determination.
431  * @param objectPointAccessor The accessor for the object points, at least one
432  * @return The resulting median position
433  * @tparam TAccessor The data type of the accessor providing the object points
434  */
435  template <typename TAccessor>
436  static inline ObjectPoint medianObjectPoint(const TAccessor& objectPointAccessor);
437 
438  /**
439  * Returns the median distance between a given 2D object point and a set of given 2D points.
440  * @param imagePoint The image point to which the median distance will be determined
441  * @param imagePointAccessor The accessor for the image points, at least one
442  * @return The resulting median distance
443  * @tparam TAccessor The data type of the accessor providing the image points
444  */
445  template <typename TAccessor>
446  static inline Scalar medianDistance(const ImagePoint& imagePoint, const TAccessor& imagePointAccessor);
447 
448  /**
449  * Returns the median distance between a given 3D object point and a set of given 3D points.
450  * @param objectPoint The object point to which the median distance will be determined
451  * @param objectPointAccessor The accessor for the object points, at least one
452  * @return The resulting median distance
453  * @tparam TAccessor The data type of the accessor providing the object points
454  */
455  template <typename TAccessor>
456  static inline Scalar medianDistance(const ObjectPoint& objectPoint, const TAccessor& objectPointAccessor);
457 
458  /**
459  * Create a random homography transformation
460  * The homography is created in such a way that points in an output image are mapped into the input image, i.e., inputPoints_i = homography * outputPoints_i
461  * @param width The width of the input image, range: [1, infinity)
462  * @param height The height of the input image, range: [1, infinity)
463  * @param maxTranslation A random global translation that is added to the random homography
464  * @return A random homography
465  */
466  static SquareMatrix3 createRandomHomography(const unsigned int width, const unsigned height, const Scalar maxTranslation);
467 
468  /**
469  * Deprecated.
470  *
471  * Returns a random 6-DOF camera pose for a pinhole camera which observes a given 3D object point at a specified 2D image point location while having a specified distance to the 3D object point.
472  * @param pinholeCamera The pinhole camera profile defining the projection, must be valid
473  * @param worldObjectPointRay The 3D ray starting at the 3D object point and pointing towards the camera's center of projection, must be valid
474  * @param distortedImagePoint The 2D image point within the fisheye camera image, with range [0, fisheyeCamera.width())x[0, fisheyeCamera.height())
475  * @param distance The desired distance between 3D object point and camera (center of projection), with range (0, infinity)
476  * @return The 6-DOF camera pose matching with the specified constraints, will be world_T_camera
477  */
478  static HomogenousMatrix4 randomCameraPose(const PinholeCamera& pinholeCamera, const Line3& worldObjectPointRay, const Vector2& distortedImagePoint, const Scalar distance);
479 
480  /**
481  * Deprecated.
482  *
483  * Returns a random 6-DOF camera pose for a fisheye camera which observes a given 3D object point at a specified 2D image point location while having a specified distance to the 3D object point.
484  * @param fisheyeCamera The fisheye camera profile defining the projection, must be valid
485  * @param worldObjectPointRay The 3D ray starting at the 3D object point and pointing towards the camera's center of projection, must be valid
486  * @param distortedImagePoint The 2D image point within the fisheye camera image, with range [0, fisheyeCamera.width())x[0, fisheyeCamera.height())
487  * @param distance The desired distance between 3D object point and camera (center of projection), with range (0, infinity)
488  * @return The 6-DOF camera pose matching with the specified constraints, will be world_T_camera
489  */
490  static HomogenousMatrix4 randomCameraPose(const FisheyeCamera& fisheyeCamera, const Line3& worldObjectPointRay, const Vector2& distortedImagePoint, const Scalar distance);
491 
492  /**
493  * Returns a random 6-DOF camera pose for any camera which observes a given 3D object point at a specified 2D image point location while having a specified distance to the 3D object point.
494  * @param anyCamera The camera profile defining the projection, must be valid
495  * @param worldObjectPointRay The 3D ray starting at the 3D object point and pointing towards the camera's center of projection, must be valid
496  * @param distortedImagePoint The 2D image point within the camera image, with range [0, anyCamera.width())x[0, anyCamera.height())
497  * @param distance The desired distance between 3D object point and camera (center of projection), with range (0, infinity)
498  * @return The 6-DOF camera pose matching with the specified constraints, will be world_T_camera
499  */
500  static HomogenousMatrix4 randomCameraPose(const AnyCamera& anyCamera, const Line3& worldObjectPointRay, const Vector2& distortedImagePoint, const Scalar distance);
501 };
502 
503 inline size_t Utilities::countFrontObjectPoints(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const ObjectPoint* objectPoints, const size_t numberObjectPoints)
504 {
505  ocean_assert(pose.isValid());
506 
507  return countFrontObjectPointsIF(pinholeCamera, PinholeCamera::standard2InvertedFlipped(pose), objectPoints, numberObjectPoints);
508 }
509 
510 inline SquareMatrix2 Utilities::covarianceMatrix(const ImagePoint* imagePoints, const size_t number, const Scalar minimalSigma)
511 {
512  return covarianceMatrix(imagePoints, number, meanImagePoint(ConstTemplateArrayAccessor<ImagePoint>(imagePoints, number)), minimalSigma);
513 }
514 
515 inline Scalar Utilities::computePolygonArea(const Vector2* vertices, size_t size)
516 {
517  return Numeric::abs(computePolygonAreaSigned(vertices, size));
518 }
519 
521 {
522  return Numeric::abs(computePolygonAreaSigned(vertices.data(), vertices.size()));
523 }
524 
526 {
527  return computePolygonAreaSigned(vertices.data(), vertices.size());
528 }
529 
530 inline bool Utilities::isInsideConvexPolygon(const Vectors2& vertices, const Vector2& point)
531 {
532  return isInsideConvexPolygon(vertices.data(), vertices.size(), point);
533 }
534 
535 inline bool Utilities::intersectConvexPolygons(const Vectors2& vertices0, const Vectors2& vertices1, Vectors2& intersectedPolygon)
536 {
537  return intersectConvexPolygons(vertices0.data(), vertices0.size(), vertices1.data(), vertices1.size(), intersectedPolygon);
538 }
539 
540 template <typename TAccessor>
541 inline ImagePoint Utilities::meanImagePoint(const TAccessor& imagePointAccessor)
542 {
543  ocean_assert(imagePointAccessor.size() > 0);
544 
545  ImagePoint meanPosition(0, 0);
546  for (size_t n = 0; n < imagePointAccessor.size(); ++n)
547  {
548  meanPosition += imagePointAccessor[n];
549  }
550 
551  return meanPosition / Scalar(imagePointAccessor.size());
552 }
553 
554 template <typename TAccessor>
555 inline ObjectPoint Utilities::meanObjectPoint(const TAccessor& objectPointAccessor)
556 {
557  ocean_assert(objectPointAccessor.size() > 0);
558 
559  ObjectPoint meanPosition(0, 0, 0);
560  for (size_t n = 0; n < objectPointAccessor.size(); ++n)
561  {
562  meanPosition += objectPointAccessor[n];
563  }
564 
565  return meanPosition / Scalar(objectPointAccessor.size());
566 }
567 
568 template <typename TAccessor>
569 inline ImagePoint Utilities::medianImagePoint(const TAccessor& imagePointAccessor)
570 {
571  ocean_assert(!imagePointAccessor.isEmpty());
572 
573  if (imagePointAccessor.size() == 1)
574  {
575  return imagePointAccessor[0];
576  }
577 
578  Scalars xValues(imagePointAccessor.size());
579  Scalars yValues(imagePointAccessor.size());
580 
581  for (size_t n = 0; n < imagePointAccessor.size(); ++n)
582  {
583  const ImagePoint& imagePoint = imagePointAccessor[n];
584 
585  xValues[n] = imagePoint.x();
586  yValues[n] = imagePoint.y();
587  }
588 
589  const Scalar xMedian = Median::median(xValues.data(), xValues.size());
590  const Scalar yMedian = Median::median(yValues.data(), yValues.size());
591 
592  return ImagePoint(xMedian, yMedian);
593 }
594 
595 template <typename TAccessor>
596 inline ObjectPoint Utilities::medianObjectPoint(const TAccessor& objectPointAccessor)
597 {
598  ocean_assert(!objectPointAccessor.isEmpty());
599 
600  if (objectPointAccessor.size() == 1)
601  {
602  return objectPointAccessor[0];
603  }
604 
605  Scalars xValues(objectPointAccessor.size());
606  Scalars yValues(objectPointAccessor.size());
607  Scalars zValues(objectPointAccessor.size());
608 
609  for (size_t n = 0; n < objectPointAccessor.size(); ++n)
610  {
611  const ObjectPoint& objectPoint = objectPointAccessor[n];
612 
613  xValues[n] = objectPoint.x();
614  yValues[n] = objectPoint.y();
615  zValues[n] = objectPoint.z();
616  }
617 
618  const Scalar xMedian = Median::median(xValues.data(), xValues.size());
619  const Scalar yMedian = Median::median(yValues.data(), yValues.size());
620  const Scalar zMedian = Median::median(zValues.data(), zValues.size());
621 
622  return ObjectPoint(xMedian, yMedian, zMedian);
623 }
624 
625 template <typename TAccessor>
626 inline Scalar Utilities::medianDistance(const ImagePoint& imagePoint, const TAccessor& imagePointAccessor)
627 {
628  Scalars sqrDistances;
629  sqrDistances.reserve(imagePointAccessor.size());
630 
631  for (size_t n = 0; n < imagePointAccessor.size(); ++n)
632  {
633  sqrDistances.push_back(imagePoint.sqrDistance(imagePointAccessor[n]));
634  }
635 
636  return Numeric::sqrt(Median::median(sqrDistances.data(), sqrDistances.size()));
637 }
638 
639 template <typename TAccessor>
640 inline Scalar Utilities::medianDistance(const ObjectPoint& objectPoint, const TAccessor& objectPointAccessor)
641 {
642  Scalars sqrDistances;
643  sqrDistances.reserve(objectPointAccessor.size());
644 
645  for (size_t n = 0; n < objectPointAccessor.size(); ++n)
646  {
647  sqrDistances.push_back(objectPoint.sqrDistance(objectPointAccessor[n]));
648  }
649 
650  return Numeric::sqrt(Median::median(sqrDistances.data(), sqrDistances.size()));
651 }
652 
653 }
654 
655 }
656 
657 #endif // META_OCEAN_GEOMETRY_UTILITIES_H
This class implements the abstract base class for all AnyCamera objects.
Definition: AnyCamera.h:130
static HomogenousMatrixT4< U > standard2InvertedFlipped(const HomogenousMatrixT4< U > &world_T_camera)
Transforms a standard homogenous 4x4 viewing (extrinsic camera) matrix into an inverted and flipped c...
Definition: Camera.h:734
This class implements a (possibly truncated) 3D cone.
Definition: Cone3.h:59
This class implements an accessor providing direct access to a constant array of elements.
Definition: Accessor.h:600
This class implements a 3D cylinder defined by its origin, axis, radius, and (signed) starting and st...
Definition: Cylinder3.h:80
This class implements utilities function for the tracking library.
Definition: geometry/Utilities.h:36
static ObjectPoints backProjectImagePoints(const AnyCamera &anyCamera, const HomogenousMatrix4 &world_T_camera, const Plane3 &plane, const ImagePoint *imagePoints, const size_t numberImagePoints, Indices32 *frontObjectPointIndices=nullptr)
Projects a set of given image points onto a 3D plane and returns the resulting 3D object points.
static ObjectPoints backProjectImagePoints(const AnyCamera &anyCamera, const HomogenousMatrix4 &world_T_camera, const Cylinder3 &cylinder, const ImagePoint *imagePoints, const size_t numberImagePoints, Indices32 &intersectingPointIndices)
Projects a set of given image points onto a 3D cylinder and returns only the resulting 3D object poin...
static bool isPolygonConvex(const Vector2 *vertices, const size_t size, const bool strict=true)
Returns whether a polygon of given 2D points is convex.
static bool decomposeCovarianceMatrix(const SquareMatrix2 &covarianceMatrix, Vector2 &direction0, Vector2 &direction1)
Decomposes a covariance matrix.
static ObjectPoints backProjectImagePoints(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Cone3 &cone, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 &intersectingPointIndices)
Deprecated.
static bool intersectConvexPolygons(const Vector2 *vertices0, const size_t size0, const Vector2 *vertices1, const size_t size1, Vectors2 &intersectedPolygon)
Computation of the intersection of two convex polygons.
static Triangles3 backProjectTriangles(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const Triangle2 *triangles, const size_t numberTriangles, const bool useDistortionParameters)
Projects a set of given 2D image triangles onto a 3D plane and returns the resulting 3D object triang...
static SquareMatrix2 covarianceMatrix(const ImagePoint *imagePoints, const size_t number, const Scalar minimalSigma=0)
Creates the covariance matrix for a given set of image points.
Definition: geometry/Utilities.h:510
static size_t countFrontObjectPoints(const PinholeCamera &cameraFirst, const PinholeCamera &cameraSecond, const HomogenousMatrix4 &poseFirst, const HomogenousMatrix4 &poseSecond, const ImagePoint *imagePointsFirst, const ImagePoint *imagePointsSecond, const size_t correspondences)
Counts the number of object points that are visible in two individual camera frames and are located i...
static SquareMatrix3 createRandomHomography(const unsigned int width, const unsigned height, const Scalar maxTranslation)
Create a random homography transformation The homography is created in such a way that points in an o...
static ImagePoint meanImagePoint(const TAccessor &imagePointAccessor)
Returns the mean position of a set of given 2D points.
Definition: geometry/Utilities.h:541
static void triangulateObjectPoints(const AnyCamera &camera0, const AnyCamera &camera1, const HomogenousMatrix4 &world_T_camera0, const HomogenousMatrix4 &world_T_camera1, const ConstIndexedAccessor< Vector2 > &imagePoints0, const ConstIndexedAccessor< Vector2 > &imagePoints1, Vectors3 &objectPoints, Indices32 &validIndices, const bool onlyFrontPoints=true, const Scalar maximalSqrError=Scalar(3 *3))
Determines 3D object points by triangulating two sets of 2D image points from different camera poses.
static ObjectPoints backProjectImagePoints(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 *frontObjectPointIndices=nullptr)
Deprecated.
static Scalar computePolygonAreaSigned(const Vector2 *vertices, size_t size)
Compute the signed area of a polygon The value of the area will be positive if the vertices are in co...
static Vectors3 createObjectPoints(const AnyCamera &camera, const HomogenousMatrix4 &world_T_camera, const ConstIndexedAccessor< Vector2 > &imagePoints, const Scalar distance)
Creates a set of 3D object points for a set of given 2D image points.
static ObjectPoints backProjectImagePoints(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Cylinder3 &cylinder, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 &intersectingPointIndices)
Deprecated.
static size_t countFrontObjectPoints(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const ObjectPoint *objectPoints, const size_t numberObjectPoints)
Counts the number of object points that are in front of a given camera.
Definition: geometry/Utilities.h:503
static ImagePoint medianImagePoint(const TAccessor &imagePointAccessor)
Returns the median position of a set of given 2D points.
Definition: geometry/Utilities.h:569
static ObjectPoint medianObjectPoint(const TAccessor &objectPointAccessor)
Returns the median position of a set of given 3D points.
Definition: geometry/Utilities.h:596
static HomogenousMatrix4 randomCameraPose(const AnyCamera &anyCamera, const Line3 &worldObjectPointRay, const Vector2 &distortedImagePoint, const Scalar distance)
Returns a random 6-DOF camera pose for any camera which observes a given 3D object point at a specifi...
static HomogenousMatrix4 randomCameraPose(const FisheyeCamera &fisheyeCamera, const Line3 &worldObjectPointRay, const Vector2 &distortedImagePoint, const Scalar distance)
Deprecated.
static ObjectPoint meanObjectPoint(const TAccessor &objectPointAccessor)
Returns the mean position of a set of given 3D points.
Definition: geometry/Utilities.h:555
static Scalar medianDistance(const ImagePoint &imagePoint, const TAccessor &imagePointAccessor)
Returns the median distance between a given 2D object point and a set of given 2D points.
Definition: geometry/Utilities.h:626
static bool isInsideConvexPolygon(const Vector2 *vertices, size_t size, const Vector2 &point)
Returns whether a given point lies inside a convex polygon.
static SquareMatrix2 covarianceMatrix(const ImagePoint *imagePoints, const size_t number, const ImagePoint &meanPoint, const Scalar minimalSigma=0)
Creates the covariance matrix for a given set of image points.
static SquareMatrix2 covarianceMatrix(const Vector2 &majorDirection, const Scalar minimalSigma=1, const Scalar minorFactor=Scalar(0.01))
Creates a covariance matrix by one given vector representing the major axis.
static SquareMatrix2 covarianceMatrix(const ImagePoint *imagePoints, const unsigned int *indices, const size_t numberIndices, const Scalar minimalSigma, ImagePoint &meanPoint)
Creates the covariance matrix for a given set of image points.
static ObjectPoints createObjectPoints(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const ConstIndexedAccessor< ImagePoint > &imagePoints, const bool useDistortionParameters, const Scalar distance)
Deprecated.
static SquareMatrix2 covarianceMatrix(const Vector2 &direction0, const Scalar sigma0, const Vector2 &direction1, const Scalar sigma1)
Creates a covariance matrix by two given orthogonal vectors.
static ObjectPoints backProjectImagePoints(const AnyCamera &anyCamera, const HomogenousMatrix4 &world_T_camera, const Cone3 &cone, const ImagePoint *imagePoints, const size_t numberImagePoints, Indices32 &intersectingPointIndices)
Projects a set of given image points onto a 3D cone and returns only the resulting 3D object points f...
static SquareMatrix2 covarianceMatrix(const Vector2 &direction0, const Vector2 &direction1)
Creates a covariance matrix by two given orthogonal vectors.
static ObjectPoint backProjectImagePoint(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const ImagePoint &imagePoint, const bool useDistortionParameters, bool *frontObjectPoint=nullptr)
Projects one image points onto a 3D plane and returns the resulting 3D object point.
static ObjectPoints backProjectImagePointsDamped(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Plane3 &plane, const ImagePoint *imagePoints, const size_t numberImagePoints, const bool useDistortionParameters, Indices32 *frontObjectPointIndices=nullptr)
Projects a set of given image points onto a 3D plane and returns the resulting 3D object points.
static size_t countFrontObjectPointsIF(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &invertedFlippedPose, const ObjectPoint *objectPoints, const size_t numberObjectPoints)
Counts the number of object points that are in front of a given camera.
static Scalar computePolygonArea(const Vector2 *vertices, size_t size)
Compute the area of a polygon.
Definition: geometry/Utilities.h:515
static HomogenousMatrix4 randomCameraPose(const PinholeCamera &pinholeCamera, const Line3 &worldObjectPointRay, const Vector2 &distortedImagePoint, const Scalar distance)
Deprecated.
bool isValid() const
Returns whether this matrix is a valid homogeneous transformation.
Definition: HomogenousMatrix4.h:1806
This class implements an infinite line in 3D space.
Definition: Line3.h:70
static T median(T *values, const size_t number)
Returns the median value in a given data array.
Definition: Median.h:1144
static T abs(const T value)
Returns the absolute value of a given value.
Definition: Numeric.h:1220
static T sqrt(const T value)
Returns the square root of a given value.
Definition: Numeric.h:1533
This class implements a 2x2 square matrix.
Definition: SquareMatrix2.h:73
This class implements a 2D triangle with Cartesian coordinates.
Definition: Triangle2.h:81
const T & x() const noexcept
Returns the x value.
Definition: Vector2.h:698
const T & y() const noexcept
Returns the y value.
Definition: Vector2.h:710
T sqrDistance(const VectorT2< T > &right) const
Returns the square distance between this 2D position and a second 2D position.
Definition: Vector2.h:633
const T & y() const noexcept
Returns the y value.
Definition: Vector3.h:812
const T & x() const noexcept
Returns the x value.
Definition: Vector3.h:800
const T & z() const noexcept
Returns the z value.
Definition: Vector3.h:824
T sqrDistance(const VectorT3< T > &right) const
Returns the square distance between this 3D position and a second 3D position.
Definition: Vector3.h:682
std::vector< Index32 > Indices32
Definition of a vector holding 32 bit index values.
Definition: Base.h:96
std::vector< ObjectPoint > ObjectPoints
Definition of a vector holding 3D object points.
Definition: geometry/Geometry.h:129
Vector3 ObjectPoint
Definition of a 3D object point.
Definition: geometry/Geometry.h:117
Vector2 ImagePoint
Definition of a 2D image point.
Definition: geometry/Geometry.h:111
float Scalar
Definition of a scalar type.
Definition: Math.h:128
std::vector< Scalar > Scalars
Definition of a vector holding Scalar objects.
Definition: Math.h:144
std::vector< Vector2 > Vectors2
Definition of a vector holding Vector2 objects.
Definition: Vector2.h:64
std::vector< Triangle3 > Triangles3
Definition of a vector holding 3D triangles.
Definition: Triangle3.h:57
std::vector< Vector3 > Vectors3
Definition of a vector holding Vector3 objects.
Definition: Vector3.h:65
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15