Ocean
PoseEstimation.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_TRACKING_MAPBUILDING_POSE_ESTIMATION_H
9 #define META_OCEAN_TRACKING_MAPBUILDING_POSE_ESTIMATION_H
10 
13 
14 #include "ocean/base/Worker.h"
15 
16 #include "ocean/math/AnyCamera.h"
18 
19 namespace Ocean
20 {
21 
22 namespace Tracking
23 {
24 
25 namespace MapBuilding
26 {
27 
28 /**
29  * This class implements functions to estimate camera poses using unified data structures.
30  * @ingroup trackingmapbuilding
31  */
32 class OCEAN_TRACKING_MAPBUILDING_EXPORT PoseEstimation
33 {
34  public:
35 
36  /**
37  * Determines the 6-DOF pose of a mono camera based on 2D/3D correspondences using unguided and guided matching based an octree and descriptor trees.
38  * @param anyCamera The camera profile to be used, must be valid
39  * @param unifiedUnguidedMatching The unified data structure holding the information for an unguided feature matching, must be valid
40  * @param unifiedGuidedMatching The unified data structure holding the information for a guided feature matching, must be valid
41  * @param randomGenerator The random generator to be used
42  * @param world_T_camera The resulting camera pose transforming camera to world, with default camera looking into the negative z-space an y-axis upwards
43  * @param minimalNumberCorrespondences The minimal number of 2D/3D correspondences so that a camera pose counts as valid, with range [4, infinity)
44  * @param maximalDescriptorDistance The maximal descriptor distance so that two descriptors are still considered to match, with range [0, infinity)
45  * @param maximalProjectionError The maximal projection error between a projected 3D object point and a 2D image point so that both points count as corresponding, in pixel, with range [0, infinity)
46  * @param inlierRate The rate of correspondence inliers within the entire set of correspondences, e.g., 0.15 means that 15% of matched features are correct and can be used to determine a valid pose, with range (0, 1]
47  * @param usedObjectPointIds Optional resulting ids of the 3D object points which have been used to determine the camera pose, nullptr if not of interest
48  * @param usedImagePointIndices Optional resulting indices of the 2D image points which have been used to determine the camera pose, nullptr if not of interest
49  * @param world_T_roughCamera Optional known rough camera pose allowing to skip the unguided matching, invalid if unknown
50  * @param worker Optional worker to distribute the computation
51  * @return True, if succeeded
52  */
53  static bool determinePose(const AnyCamera& anyCamera, const UnifiedUnguidedMatching& unifiedUnguidedMatching, const UnifiedGuidedMatching& unifiedGuidedMatching, RandomGenerator& randomGenerator, HomogenousMatrix4& world_T_camera, const unsigned int minimalNumberCorrespondences, const UnifiedMatching::DistanceValue& maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate = Scalar(0.15), Indices32* usedObjectPointIds = nullptr, Indices32* usedImagePointIndices = nullptr, const HomogenousMatrix4& world_T_roughCamera = HomogenousMatrix4(false), Worker* worker = nullptr);
54 
55  /**
56  * Determines the 6-DOF pose of a stereo camera based on for 2D/3D correspondences using unguided and guided matching based an octree and descriptor trees.
57  * @param anyCameraA The camera profile of the first stereo camera to be used, must be valid
58  * @param anyCameraB The camera profile of the second stereo camera to be used, must be valid
59  * @param device_T_cameraA The transformation between the first camera and the device, with default camera pointing towards the negative z-space with y-axis up, must be valid
60  * @param device_T_cameraB The transformation between the second camera and the device, with default camera pointing towards the negative z-space with y-axis up, must be valid
61  * @param unifiedUnguidedMatchingA The unified data structure holding the information for an unguided feature matching for the first frame, must be valid
62  * @param unifiedUnguidedMatchingB The unified data structure holding the information for an unguided feature matching for the second frame, must be valid
63  * @param unifiedGuidedMatchingA The unified data structure holding the information for a guided feature matching for the first frame, must be valid
64  * @param unifiedGuidedMatchingB The unified data structure holding the information for a guided feature matching for the second frame, must be valid
65  * @param randomGenerator The random generator to be used
66  * @param world_T_device The resulting device pose transforming device to world
67  * @param minimalNumberCorrespondences The minimal number of 2D/3D correspondences so that a camera pose counts as valid, with range [4, infinity)
68  * @param maximalDescriptorDistance The maximal descriptor distance so that two descriptors are still considered to match, with range [0, infinity)
69  * @param maximalProjectionError The maximal projection error between a projected 3D object point and a 2D image point so that both points count as corresponding, in pixel, with range [0, infinity)
70  * @param inlierRate The rate of correspondence inliers within the entire set of correspondences, e.g., 0.15 means that 15% of matched features are correct and can be used to determine a valid pose, with range (0, 1]
71  * @param usedObjectPointIdsA Optional resulting ids of the 3D object points which have been used to determine the camera pose in the first frame, nullptr if not of interest
72  * @param usedObjectPointIdsB Optional resulting ids of the 3D object points which have been used to determine the camera pose in the second frame, nullptr if not of interest
73  * @param usedImagePointIndicesA Optional resulting indices of the 2D image points which have been used to determine the camera pose in the first frame, nullptr if not of interest
74  * @param usedImagePointIndicesB Optional resulting indices of the 2D image points which have been used to determine the camera pose in the second frame, nullptr if not of interest
75  * @param world_T_roughDevice Optional known rough device pose allowing to skip the unguided matching, invalid if unknown
76  * @param worker Optional worker to distribute the computation
77  * @return True, if succeeded
78  */
79  static bool determinePose(const AnyCamera& anyCameraA, const AnyCamera& anyCameraB, const HomogenousMatrix4& device_T_cameraA, const HomogenousMatrix4& device_T_cameraB, const UnifiedUnguidedMatching& unifiedUnguidedMatchingA, const UnifiedUnguidedMatching& unifiedUnguidedMatchingB, const UnifiedGuidedMatching& unifiedGuidedMatchingA, const UnifiedGuidedMatching& unifiedGuidedMatchingB, RandomGenerator& randomGenerator, HomogenousMatrix4& world_T_device, const unsigned int minimalNumberCorrespondences, const UnifiedMatching::DistanceValue& maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate = Scalar(0.15), Indices32* usedObjectPointIdsA = nullptr, Indices32* usedObjectPointIdsB = nullptr, Indices32* usedImagePointIndicesA = nullptr, Indices32* usedImagePointIndicesB = nullptr, const HomogenousMatrix4& world_T_roughDevice = HomogenousMatrix4(false), Worker* worker = nullptr);
80 };
81 
82 }
83 
84 }
85 
86 }
87 
88 #endif // META_OCEAN_TRACKING_MAPBUILDING_POSE_ESTIMATION_H
This class implements the abstract base class for all AnyCamera objects.
Definition: AnyCamera.h:130
This class implements a generator for random numbers.
Definition: RandomGenerator.h:42
This class implements functions to estimate camera poses using unified data structures.
Definition: PoseEstimation.h:33
static bool determinePose(const AnyCamera &anyCamera, const UnifiedUnguidedMatching &unifiedUnguidedMatching, const UnifiedGuidedMatching &unifiedGuidedMatching, RandomGenerator &randomGenerator, HomogenousMatrix4 &world_T_camera, const unsigned int minimalNumberCorrespondences, const UnifiedMatching::DistanceValue &maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate=Scalar(0.15), Indices32 *usedObjectPointIds=nullptr, Indices32 *usedImagePointIndices=nullptr, const HomogenousMatrix4 &world_T_roughCamera=HomogenousMatrix4(false), Worker *worker=nullptr)
Determines the 6-DOF pose of a mono camera based on 2D/3D correspondences using unguided and guided m...
static bool determinePose(const AnyCamera &anyCameraA, const AnyCamera &anyCameraB, const HomogenousMatrix4 &device_T_cameraA, const HomogenousMatrix4 &device_T_cameraB, const UnifiedUnguidedMatching &unifiedUnguidedMatchingA, const UnifiedUnguidedMatching &unifiedUnguidedMatchingB, const UnifiedGuidedMatching &unifiedGuidedMatchingA, const UnifiedGuidedMatching &unifiedGuidedMatchingB, RandomGenerator &randomGenerator, HomogenousMatrix4 &world_T_device, const unsigned int minimalNumberCorrespondences, const UnifiedMatching::DistanceValue &maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate=Scalar(0.15), Indices32 *usedObjectPointIdsA=nullptr, Indices32 *usedObjectPointIdsB=nullptr, Indices32 *usedImagePointIndicesA=nullptr, Indices32 *usedImagePointIndicesB=nullptr, const HomogenousMatrix4 &world_T_roughDevice=HomogenousMatrix4(false), Worker *worker=nullptr)
Determines the 6-DOF pose of a stereo camera based on for 2D/3D correspondences using unguided and gu...
This class implements the base class for all guided matching objects.
Definition: UnifiedMatching.h:166
Definition of a descriptor distance value.
Definition: UnifiedMatching.h:52
This class implements the base class for all unguided matching objects.
Definition: UnifiedMatching.h:227
This class implements a worker able to distribute function calls over different threads.
Definition: Worker.h:33
std::vector< Index32 > Indices32
Definition of a vector holding 32 bit index values.
Definition: Base.h:96
float Scalar
Definition of a scalar type.
Definition: Math.h:128
HomogenousMatrixT4< Scalar > HomogenousMatrix4
Definition of the HomogenousMatrix4 object, depending on the OCEAN_MATH_USE_SINGLE_PRECISION flag eit...
Definition: HomogenousMatrix4.h:37
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15