Ocean
Loading...
Searching...
No Matches
PoseEstimationT.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_POSE_ESTIMATION_T_H
9#define META_OCEAN_TRACKING_POSE_ESTIMATION_T_H
10
13
14#include "ocean/base/Worker.h"
15
19
22#include "ocean/math/Vector2.h"
23#include "ocean/math/Vector3.h"
24
25namespace Ocean
26{
27
28namespace Tracking
29{
30
31/**
32 * This class implements functions to estimate camera poses using template-based data types.
33 * @ingroup tracking
34 */
35class OCEAN_TRACKING_EXPORT PoseEstimationT
36{
37 public:
38
39 /**
40 * Definition of an unordered map mapping object point ids to descriptors.
41 */
42 template <typename TDescriptor>
43 using UnorderedDescriptorMap = std::unordered_map<Index32, TDescriptor>;
44
45 public:
46
47 /**
48 * Determines the 6-DOF pose for 2D/3D correspondences applying a brute-force search.
49 * The function can be used to verify the performance/correctness of pose estimation functions avoiding a brute-force search.
50 * @param camera The camera profile to be used, must be valid
51 * @param objectPoints The 3D object points of all possible 3D features, must be valid
52 * @param objectPointDescriptors The descriptors for all 3D object points, one descriptor for each 3D object point (however, TObjectPointDescriptor allows to e.g., define a array/vector of several descriptors per object point), must be valid
53 * @param numberObjectPoints The number of given 3D object points (and object point descriptors), with range [4, infinity)
54 * @param imagePoints The 2D image points of all possible 2D features, must be valid
55 * @param imagePointDescriptors The descriptors for all 2D image points, one for each image points, must be valid
56 * @param numberImagePoints The number of 2D image points, with range [4, infinity)
57 * @param randomGenerator The random generator to be used
58 * @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
59 * @param minimalNumberCorrespondences The minimal number of 2D/3D correspondences so that a camera pose counts as valid, with range [4, infinity)
60 * @param maximalDescriptorDistance The maximal descriptor distance so that two descriptors are still considered to match, with range [0, infinity)
61 * @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)
62 * @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]
63 * @param usedObjectPointIndices Optional resulting indices of the 3D object points which have been used to determine the camera pose, nullptr if not of interest
64 * @param usedImagePointIndices Optional resulting indices of the 2D image points which have been used to determine the camera pose, nullptr if not of interest
65 * @param world_T_roughCamera Optional known rough camera pose allowing to skip the unguided matching, invalid if unknown
66 * @param worker Optional worker to distribute the computation
67 * @param gravityConstraints Optional gravity constraints to guide the pose estimation, nullptr otherwise
68 * @return True, if succeeded
69 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
70 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
71 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
72 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
73 */
74 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
75 static bool determinePoseBruteForce(const AnyCamera& camera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPoints, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, RandomGenerator& randomGenerator, HomogenousMatrix4& world_T_camera, const unsigned int minimalNumberCorrespondences, const TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate = Scalar(0.15), Indices32* usedObjectPointIndices = nullptr, Indices32* usedImagePointIndices = nullptr, const HomogenousMatrix4& world_T_roughCamera = HomogenousMatrix4(false), Worker* worker = nullptr, const Geometry::GravityConstraints* gravityConstraints = nullptr);
76
77 /**
78 * Determines the 6-DOF pose for 2D/3D correspondences applying a brute-force search.
79 * The function can be used to verify the performance/correctness of pose estimation functions avoiding a brute-force search.
80 * This function uses descriptors for 3D object points which can be stored in an arbitrary order (even multiple individual descriptors can exist for one 3D object point).
81 * The relationship between object point descriptors and their corresponding 3D object point locations is defined via 'objectPointIndices'.
82 * @param camera The camera profile to be used, must be valid
83 * @param objectPoints The 3D object points of all possible 3D features, must be valid
84 * @param objectPointDescriptors The descriptors for all 3D object points, some descriptors may describe the same 3D object points (e.g., because of different viewing locations), must be valid
85 * @param objectPointIndices The indices of the corresponding 3D object points, one for each object point descriptor, mainly a map mapping descriptor indices to point indices, must be valid
86 * @param numberObjectDescriptors The number of given descriptors for the 3D object points, with range [4, infinity)
87 * @param imagePoints The 2D image points of all possible 2D features, must be valid
88 * @param imagePointDescriptors The descriptors for all 2D image points, one for each image points, must be valid
89 * @param numberImagePoints The number of 2D image points, with range [4, infinity)
90 * @param randomGenerator The random generator to be used
91 * @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
92 * @param minimalNumberCorrespondences The minimal number of 2D/3D correspondences so that a camera pose counts as valid, with range [4, infinity)
93 * @param maximalDescriptorDistance The maximal descriptor distance so that two descriptors are still considered to match, with range [0, infinity)
94 * @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)
95 * @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]
96 * @param usedObjectPointIndices Optional resulting indices of the 3D object points which have been used to determine the camera pose, nullptr if not of interest
97 * @param usedImagePointIndices Optional resulting indices of the 2D image points which have been used to determine the camera pose, nullptr if not of interest
98 * @param world_T_roughCamera Optional known rough camera pose allowing to skip the unguided matching, invalid if unknown
99 * @return True, if succeeded
100 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
101 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
102 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
103 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
104 */
105 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
106 static bool determinePoseBruteForceWithArbitraryDescriptorOrder(const AnyCamera& camera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const Index32* objectPointIndices, const size_t numberObjectDescriptors, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, RandomGenerator& randomGenerator, HomogenousMatrix4& world_T_camera, const unsigned int minimalNumberCorrespondences, const TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate = Scalar(0.15), Indices32* usedObjectPointIndices = nullptr, Indices32* usedImagePointIndices = nullptr, const HomogenousMatrix4& world_T_roughCamera = HomogenousMatrix4(false));
107
108 /**
109 * Determines the unguided matching (without apriori information) between image point and object point features applying a brute-force search.
110 * @param objectPointDescriptors The object point descriptors to be used, must be valid
111 * @param numberObjectPointDescriptors The number of given object point descriptors, with range [1, infinity)
112 * @param imagePointDescriptors The image point descriptors to be used, must be valid
113 * @param numberImagePointDescriptors The number of given image point descriptors, with range [1, infinity)
114 * @param maximalDescriptorDistance The maximal distance between two corresponding descriptors, with range [0, infinity)
115 * @param objectPointDescriptorIndices The resulting indices of object point descriptors matching to the individual image point descriptors, one object point descriptor index of each given image point descriptor, -1 for image point descriptors for which no matching object point descriptor could be found
116 * @param worker Optional worker to distribute the computation
117 * @param distances Optional resulting distances between the individual matched descriptors, one for each image point descriptor, undefined if no matching exists, nullptr if not of interest
118 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
119 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
120 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
121 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
122 */
123 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
124 static void determineUnguidedBruteForceMatchings(const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPointDescriptors, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePointDescriptors, TDescriptorDistance maximalDescriptorDistance, Index32* objectPointDescriptorIndices, Worker* worker, TDescriptorDistance* distances = nullptr);
125
126 /**
127 * Determines the guided matching (with known rough camera pose) between image point and object point features applying a brute-force search.
128 * @param camera The camera profile defining the projection, must be valid
129 * @param world_T_roughCamera The known rough camera pose transforming camera to world, must be valid
130 * @param objectPoints The 3D object points to be used, must be valid
131 * @param objectPointDescriptors The object point descriptors, one for each 3D object point, must be valid
132 * @param numberObjectPoints The number of given object points (and object point descriptors), with range [1, infinity)
133 * @param imagePoints The 2D image points to be used, must be valid
134 * @param imagePointDescriptors The image point descriptors, one for each 2D image point, must be valid
135 * @param numberImagePoints The number of given image points (and image point descriptors), with range [1, infinity)
136 * @param maximalDescriptorDistance The maximal distance between two corresponding descriptors, with range [0, infinity)
137 * @param maximalProjectionError The maximal projection error of valid 2D/3D feature correspondences, in pixel, with range [0, infinity)
138 * @param objectPointDescriptorIndices The resulting indices of object point descriptors matching to the individual image point descriptors, one object point descriptor index of each given image point descriptor, -1 for image point descriptors for which no matching object point descriptor could be found
139 * @param worker Optional worker to distribute the computation
140 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
141 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
142 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
143 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
144 */
145 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
146 static void determineGuidedBruteForceMatchings(const AnyCamera& camera, const HomogenousMatrix4& world_T_roughCamera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPoints, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, Index32* objectPointDescriptorIndices, Worker* worker);
147
148 /**
149 * Determines the guided matching between 2D/3D correspondences.
150 * @param camera The camera profile to be used, must be valid
151 * @param world_T_camera The known (rough) camera pose transforming camera to world, with default camera looking into the negative z-space an y-axis upwards, must be valid
152 * @param imagePoints The 2D image points of all possible 2D features, must be valid
153 * @param imagePointDescriptors The descriptors for all 2D image points, one for each image points, must be valid
154 * @param numberImagePoints The number of 2D image points, with range [4, infinity)
155 * @param objectPoints The 3D object points of all possible 3D features, must be valid
156 * @param objectPointOctree The octree with all 3D object points
157 * @param objectPointIds The ids of all 3D object points, one for each 3D object point, must be valid
158 * @param objectPointDescriptorMap The map mapping 3D object point ids to their descriptors
159 * @param matchedImagePoints The resulting 2D image points which have been determined during the matching
160 * @param matchedObjectPoints The resulting 3D object points which have been determined during the matching
161 * @param maximalDescriptorDistance The maximal descriptor distance so that two descriptors are still considered to match, with range [0, infinity)
162 * @param matchedImagePointIndices Optional resulting indices of the image points which have been matched, one for each resulting 2D image points, nullptr if not of interest
163 * @param matchedObjectPointIds Optional resulting object point ids of the object points which have been matched, one for each resulting 3D image points, nullptr if not of interest
164 * @param worker Optional worker to distribute the computation
165 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
166 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
167 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
168 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
169 */
170 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
171 static void determineGuidedMatchings(const AnyCamera& camera, const HomogenousMatrix4& world_T_camera, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, const Vector3* objectPoints, const Geometry::Octree& objectPointOctree, const Index32* objectPointIds, const UnorderedDescriptorMap<TObjectPointDescriptor>& objectPointDescriptorMap, Vectors2& matchedImagePoints, Vectors3& matchedObjectPoints, const TDescriptorDistance maximalDescriptorDistance, Indices32* matchedImagePointIndices = nullptr, Indices32* matchedObjectPointIds = nullptr, Worker* worker = nullptr);
172
173 /**
174 * Returns the individual descriptor distances for a given set of corresponding feature descriptor pairs.
175 * This function can be used to e.g., analyze the distribution of descriptor distances and e.g., to determine an ideal threshold for valid descriptor correspondences.
176 * @param objectPointDescriptors The descriptors of the object points, must be valid
177 * @param imagePointDescriptors The descriptors of the image points, must be valid
178 * @param objectPointDescriptorIndices The indices of the object point descriptors for which a corresponding image point descriptor exists, must be valid
179 * @param imagePointDescriptorIndices The indices of the image point descriptors for which a corresponding object point descriptor exists, one for each object point descriptor, with the same order as the object point descriptors, must be valid
180 * @param numberCorrespondences The number of specified descriptor correspondences, with range [1, infinity)
181 * @return The descriptor distances, one of each corresponding descriptor pair, in the same order as the provided correspondences
182 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
183 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
184 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
185 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
186 */
187 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
188 static std::vector<TDescriptorDistance> determineDescriptorDistances(const TObjectPointDescriptor* objectPointDescriptors, const TImagePointDescriptor* imagePointDescriptors, const Index32* objectPointDescriptorIndices, const Index32* imagePointDescriptorIndices, const size_t numberCorrespondences);
189
190 protected:
191
192 /**
193 * Determines the unguided matching between a subset of image point and object point features applying a brute-force search.
194 * @param objectPointDescriptors The object point descriptors to be used, must be valid
195 * @param numberObjectPointDescriptors The number of given object point descriptors, with range [1, infinity)
196 * @param imagePointDescriptors The image point descriptors to be used, must be valid
197 * @param maximalDescriptorDistance The maximal distance between two corresponding descriptors, with range [0, infinity)
198 * @param objectPointDescriptorIndices The resulting indices of object point descriptors matching to the individual image point descriptors, one object point descriptor index of each given image point descriptor, -1 for image point descriptors for which no matching object point descriptor could be found
199 * @param distances Optional resulting distances between the individual matched descriptors, one for each image point descriptor, nullptr if not of interest
200 * @param firstImagePointDescriptor The first image point descriptor to be handled, with range [0, numberImagePointDescriptors - 1]
201 * @param numberImagePointDescriptors The number of image point descriptors to be handled, with range [1, numberImagePointDescriptors - firstImagePointDescriptor]
202 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
203 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
204 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
205 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
206 */
207 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
208 static void determineUnguidedBruteForceMatchingsSubset(const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPointDescriptors, const TImagePointDescriptor* imagePointDescriptors, TDescriptorDistance maximalDescriptorDistance, Index32* objectPointDescriptorIndices, TDescriptorDistance* distances, const unsigned int firstImagePointDescriptor, const unsigned int numberImagePointDescriptors);
209
210 /**
211 * Determines the guided matching (without known rough camera pose) between a subset of image point and object point features applying a brute-force search.
212 * @param camera The camera profile defining the projection, must be valid
213 * @param world_T_roughCamera The known rough camera pose transforming camera to world, must be valid
214 * @param objectPoints The 3D object points to be used, must be valid
215 * @param objectPointDescriptors The object point descriptors, one for each 3D object point, must be valid
216 * @param numberObjectPoints The number of given object points (and object point descriptors), with range [1, infinity)
217 * @param imagePoints The 2D image points to be used, must be valid
218 * @param imagePointDescriptors The image point descriptors, one for each 2D image point, must be valid
219 * @param maximalDescriptorDistance The maximal distance between two corresponding descriptors, with range [0, infinity)
220 * @param maximalProjectionError The maximal projection error of valid 2D/3D feature correspondences, in pixel, with range [0, infinity)
221 * @param objectPointDescriptorIndices The resulting indices of object point descriptors matching to the individual image point descriptors, one object point descriptor index of each given image point descriptor, -1 for image point descriptors for which no matching object point descriptor could be found
222 * @param firstImagePoint The first image point to be handled, with range [0, numberImagePoints - 1]
223 * @param numberImagePoints The number of image points to be handled, with range [1, numberImagePoints - firstImagePoint]
224 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
225 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
226 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
227 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
228 */
229 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
230 static void determineGuidedBruteForceMatchingsSubset(const AnyCamera* camera, const HomogenousMatrix4* world_T_roughCamera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPoints, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, Index32* objectPointDescriptorIndices, const unsigned int firstImagePoint, const unsigned int numberImagePoints);
231
232 /**
233 * Determines the guided matching between 2D/3D correspondences for a subset of the given 2D image points.
234 * @param camera The camera profile to be used, must be valid
235 * @param world_T_camera The known (rough) camera pose transforming camera to world, with default camera looking into the negative z-space an y-axis upwards, must be valid
236 * @param imagePoints The 2D image points of all possible 2D features, must be valid
237 * @param imagePointDescriptors The descriptors for all 2D image points, one for each image points, must be valid
238 * @param objectPoints The 3D object points of all possible 3D features, must be valid
239 * @param objectPointOctree The octree with all 3D object points
240 * @param objectPointIds The ids of all 3D object points, one for each 3D object point, must be valid
241 * @param objectPointDescriptorMap The map mapping 3D object point ids to their descriptors
242 * @param matchedImagePoints The resulting 2D image points which have been determined during the matching
243 * @param matchedObjectPoints The resulting 3D object points which have been determined during the matching
244 * @param maximalDescriptorDistance The maximal descriptor distance so that two descriptors are still considered to match, with range [0, infinity)
245 * @param matchedImagePointIndices The resulting indices of the image points which have been matched, one for each resulting 2D image points, nullptr if not of interest
246 * @param matchedObjectPointIds The resulting object point ids of the object points which have been matched, one for each resulting 3D image points, nullptr if not of interest
247 * @param lock The lock object in case this function is executed across multiple thread, nullptr if executed in one thread
248 * @param firstImagePoint The index of the first image point to be handled, with range [0, numberImagePoints - 1]
249 * @param numberImagePoints The number of image points to be handled, with range [1, numberImagePoints - firstImagePoint]
250 * @tparam TImagePointDescriptor The data type of the descriptor for the 2D image points
251 * @tparam TObjectPointDescriptor The data type of the descriptor for the 3D object points
252 * @tparam TDescriptorDistance The data type of the distance between image point and object point descriptors, e.g., 'uint32_t' or 'float'
253 * @tparam tImageObjectDistanceFunction The function pointer to a function allowing to determine the descriptor distance between an image point feature descriptor and an object point feature descriptor, must be valid
254 */
255 template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
256 static void determineGuidedMatchingsSubset(const AnyCamera* camera, const HomogenousMatrix4* world_T_camera, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const Vector3* objectPoints, const Geometry::Octree* objectPointOctree, const Index32* objectPointIds, const UnorderedDescriptorMap<TObjectPointDescriptor>* objectPointDescriptorMap, Vectors2* matchedImagePoints, Vectors3* matchedObjectPoints, Indices32* matchedImagePointIndices, Indices32* matchedObjectPointIds, const TDescriptorDistance maximalDescriptorDistance, Lock* lock, const unsigned int firstImagePoint, const unsigned int numberImagePoints);
257};
258
259template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
260bool PoseEstimationT::determinePoseBruteForce(const AnyCamera& camera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPoints, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, RandomGenerator& randomGenerator, HomogenousMatrix4& world_T_camera, const unsigned int minimalNumberCorrespondences, const TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate, Indices32* usedObjectPointIndices, Indices32* usedImagePointIndices, const HomogenousMatrix4& world_T_roughCamera, Worker* worker, const Geometry::GravityConstraints* gravityConstraints)
261{
262 ocean_assert(camera.isValid());
263
264 ocean_assert(maximalProjectionError >= Scalar(0));
265 ocean_assert(inlierRate > Scalar(0) && inlierRate <= Scalar(1));
266
267 if (numberImagePoints < size_t(minimalNumberCorrespondences))
268 {
269 return false;
270 }
271
272 const Scalar maximalSqrProjectionError = maximalProjectionError * maximalProjectionError;
273
274 Indices32 matchedObjectPointIds(numberImagePoints);
275
276 Vectors2 matchedImagePoints;
277 Vectors3 matchedObjectPoints;
278
279 matchedImagePoints.reserve(numberImagePoints);
280 matchedObjectPoints.reserve(numberImagePoints);
281
282 if (!world_T_roughCamera.isValid())
283 {
284 determineUnguidedBruteForceMatchings<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>(objectPointDescriptors, numberObjectPoints, imagePointDescriptors, numberImagePoints, maximalDescriptorDistance, matchedObjectPointIds.data(), worker);
285
286 for (size_t imagePointIndex = 0; imagePointIndex < numberImagePoints; ++imagePointIndex)
287 {
288 const Index32& matchedObjectPointIndex = matchedObjectPointIds[imagePointIndex];
289
290 if (matchedObjectPointIndex != Index32(-1))
291 {
292 matchedImagePoints.emplace_back(imagePoints[imagePointIndex]);
293 matchedObjectPoints.emplace_back(objectPoints[matchedObjectPointIndex]);
294 }
295 }
296
297 ocean_assert(matchedImagePoints.size() == matchedObjectPoints.size());
298
299 if (matchedImagePoints.size() < size_t(minimalNumberCorrespondences))
300 {
301 world_T_camera.toNull();
302 return false;
303 }
304 }
305
306 Indices32 internalUsedObjectPointIndices;
307 Indices32 internalUsedImagePointIndices;
308
309 const bool useInternalIndices = usedObjectPointIndices != nullptr || usedImagePointIndices != nullptr;
310
311 if (useInternalIndices)
312 {
313 internalUsedObjectPointIndices.reserve(numberImagePoints);
314 internalUsedImagePointIndices.reserve(numberImagePoints);
315 }
316
317 const Scalar faultyRate = Scalar(1) - inlierRate;
318 ocean_assert(faultyRate >= Scalar(0) && faultyRate < Scalar(1));
319
320 const unsigned int unguidedIterations = Geometry::RANSAC::iterations(3u, Scalar(0.99), faultyRate);
321
322 Indices32 validIndices;
323 if (world_T_roughCamera.isValid() || Geometry::RANSAC::p3p(camera, ConstArrayAccessor<Vector3>(matchedObjectPoints), ConstArrayAccessor<Vector2>(matchedImagePoints), randomGenerator, world_T_camera, 20u, true, unguidedIterations, maximalSqrProjectionError, &validIndices, nullptr, gravityConstraints))
324 {
325 // now applying guided matching
326
327 if (world_T_roughCamera.isValid())
328 {
329 world_T_camera = world_T_roughCamera;
330 }
331
332 matchedImagePoints.clear();
333 matchedObjectPoints.clear();
334
335 determineGuidedBruteForceMatchings<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>(camera, world_T_camera, objectPoints, objectPointDescriptors, numberObjectPoints, imagePoints, imagePointDescriptors, numberImagePoints, maximalDescriptorDistance, maximalProjectionError, matchedObjectPointIds.data(), worker);
336
337 for (size_t imagePointIndex = 0; imagePointIndex < numberImagePoints; ++imagePointIndex)
338 {
339 const Index32& matchedObjectPointIndex = matchedObjectPointIds[imagePointIndex];
340
341 if (matchedObjectPointIndex != Index32(-1))
342 {
343 matchedImagePoints.emplace_back(imagePoints[imagePointIndex]);
344 matchedObjectPoints.emplace_back(objectPoints[matchedObjectPointIndex]);
345
346 if (useInternalIndices)
347 {
348 internalUsedImagePointIndices.emplace_back(Index32(imagePointIndex));
349 internalUsedObjectPointIndices.emplace_back(matchedObjectPointIndex);
350 }
351 }
352 }
353
354 if (matchedImagePoints.size() < size_t(minimalNumberCorrespondences))
355 {
356 world_T_camera.toNull();
357 return false;
358 }
359
360 constexpr unsigned int guidedIterations = 40u;
361
362 world_T_camera.toNull();
363 validIndices.clear();
364 if (Geometry::RANSAC::p3p(camera, ConstArrayAccessor<Vector3>(matchedObjectPoints), ConstArrayAccessor<Vector2>(matchedImagePoints), randomGenerator, world_T_camera, 20u, true, guidedIterations, maximalSqrProjectionError, &validIndices, nullptr, gravityConstraints))
365 {
366 if (validIndices.size() < size_t(minimalNumberCorrespondences))
367 {
368 world_T_camera.toNull();
369 return false;
370 }
371
372 if (usedObjectPointIndices != nullptr)
373 {
374 ocean_assert(useInternalIndices);
375
376 usedObjectPointIndices->clear();
377 usedObjectPointIndices->reserve(validIndices.size());
378
379 for (const Index32 validIndex : validIndices)
380 {
381 usedObjectPointIndices->emplace_back(internalUsedObjectPointIndices[validIndex]);
382 }
383 }
384
385 if (usedImagePointIndices != nullptr)
386 {
387 ocean_assert(useInternalIndices);
388
389 usedImagePointIndices->clear();
390 usedImagePointIndices->reserve(validIndices.size());
391
392 for (const Index32 validIndex : validIndices)
393 {
394 usedImagePointIndices->emplace_back(internalUsedImagePointIndices[validIndex]);
395 }
396
397 ocean_assert(UnorderedIndexSet32(usedImagePointIndices->cbegin(), usedImagePointIndices->cend()).size() == usedImagePointIndices->size());
398 }
399
400 if (usedObjectPointIndices != nullptr && usedImagePointIndices != nullptr)
401 {
402 // let's ensure that each object point is used only by one image point
403
404 ocean_assert(UnidirectionalCorrespondences::countBijectiveCorrespondences(usedImagePointIndices->data(), usedImagePointIndices->size()) == usedImagePointIndices->size());
405
406 UnidirectionalCorrespondences::removeNonBijectiveCorrespondences(camera, world_T_camera, objectPoints, imagePoints, *usedObjectPointIndices, *usedImagePointIndices, false /*checkImagePoints*/);
407
408 ocean_assert(UnidirectionalCorrespondences::countBijectiveCorrespondences(usedImagePointIndices->data(), usedImagePointIndices->size()) == usedImagePointIndices->size());
409 ocean_assert(UnidirectionalCorrespondences::countBijectiveCorrespondences(usedObjectPointIndices->data(), usedObjectPointIndices->size()) == usedObjectPointIndices->size());
410
411 if (usedObjectPointIndices->size() < size_t(minimalNumberCorrespondences))
412 {
413 world_T_camera.toNull();
414 return false;
415 }
416 }
417
418 return true;
419 }
420 }
421
422 world_T_camera.toNull();
423
424 return false;
425}
426
427template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
428bool PoseEstimationT::determinePoseBruteForceWithArbitraryDescriptorOrder(const AnyCamera& camera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const Index32* objectPointIndices, const size_t numberObjectDescriptors, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, RandomGenerator& randomGenerator, HomogenousMatrix4& world_T_camera, const unsigned int minimalNumberCorrespondences, const TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate, Indices32* usedObjectPointIndices, Indices32* usedImagePointIndices, const HomogenousMatrix4& world_T_roughCamera)
429{
430 ocean_assert(camera.isValid());
431
432 ocean_assert(maximalProjectionError >= Scalar(0));
433 ocean_assert(inlierRate > Scalar(0) && inlierRate <= Scalar(1));
434
435 if (numberImagePoints < size_t(minimalNumberCorrespondences))
436 {
437 return false;
438 }
439
440 const Scalar maximalSqrProjectionError = maximalProjectionError * maximalProjectionError;
441
442 Vectors2 matchedImagePoints;
443 Vectors3 matchedObjectPoints;
444
445 matchedImagePoints.reserve(numberImagePoints);
446 matchedObjectPoints.reserve(numberImagePoints);
447
448 if (!world_T_roughCamera.isValid())
449 {
450 // unguided brute force matching
451
452 for (size_t imagePointIndex = 0; imagePointIndex < numberImagePoints; ++imagePointIndex)
453 {
454 const TImagePointDescriptor& imagePointDescriptor = imagePointDescriptors[imagePointIndex];
455
456 TDescriptorDistance bestDistance = NumericT<TDescriptorDistance>::maxValue();
457 Index32 bestObjectPointDescriptorIndex = Index32(-1);
458
459 for (size_t nObjectPoint = 0; nObjectPoint < numberObjectDescriptors; ++nObjectPoint)
460 {
461 const TDescriptorDistance distance = tImageObjectDistanceFunction(imagePointDescriptor, objectPointDescriptors[nObjectPoint]);
462
463 if (distance < bestDistance)
464 {
465 bestDistance = distance;
466 bestObjectPointDescriptorIndex = Index32(nObjectPoint);
467 }
468 }
469
470 if (bestDistance <= maximalDescriptorDistance)
471 {
472 const Index32 objectPointIndex = objectPointIndices[bestObjectPointDescriptorIndex];
473
474 matchedImagePoints.emplace_back(imagePoints[imagePointIndex]);
475 matchedObjectPoints.emplace_back(objectPoints[objectPointIndex]);
476 }
477 }
478
479 if (matchedImagePoints.size() < size_t(minimalNumberCorrespondences))
480 {
481 world_T_camera.toNull();
482 return false;
483 }
484 }
485
486 Indices32 internalUsedObjectPointIndices;
487 Indices32 internalUsedImagePointIndices;
488
489 const bool useInternalIndices = usedObjectPointIndices != nullptr || usedImagePointIndices != nullptr;
490
491 if (useInternalIndices)
492 {
493 internalUsedObjectPointIndices.reserve(numberImagePoints);
494 internalUsedImagePointIndices.reserve(numberImagePoints);
495 }
496
497 const Scalar faultyRate = Scalar(1) - inlierRate;
498 ocean_assert(faultyRate >= Scalar(0) && faultyRate < Scalar(1));
499
500 const unsigned int unguidedIterations = Geometry::RANSAC::iterations(3u, Scalar(0.99), faultyRate);
501
502 Indices32 validIndices;
503 if (world_T_roughCamera.isValid() || Geometry::RANSAC::p3p(camera, ConstArrayAccessor<Vector3>(matchedObjectPoints), ConstArrayAccessor<Vector2>(matchedImagePoints), randomGenerator, world_T_camera, 20u, true, unguidedIterations, maximalSqrProjectionError, &validIndices))
504 {
505 // now applying guided matching
506
507 if (world_T_roughCamera.isValid())
508 {
509 world_T_camera = world_T_roughCamera;
510 }
511
512 matchedImagePoints.clear();
513 matchedObjectPoints.clear();
514
515 const HomogenousMatrix4 flippedCamera_T_world(Camera::standard2InvertedFlipped(world_T_camera));
516
517 for (size_t imagePointIndex = 0; imagePointIndex < numberImagePoints; ++imagePointIndex)
518 {
519 const Vector2& imagePoint = imagePoints[imagePointIndex];
520 const TImagePointDescriptor& imagePointDescriptor = imagePointDescriptors[imagePointIndex];
521
522 TDescriptorDistance bestDistance = NumericT<TDescriptorDistance>::maxValue();
523 Index32 bestObjectPointDescriptorIndex = Index32(-1);
524
525 for (size_t nObjectPoint = 0; nObjectPoint < numberObjectDescriptors; ++nObjectPoint)
526 {
527 const TDescriptorDistance distance = tImageObjectDistanceFunction(imagePointDescriptor, objectPointDescriptors[nObjectPoint]);
528
529 if (distance < bestDistance)
530 {
531 const Index32 objectPointIndex = objectPointIndices[nObjectPoint];
532
533 const Vector3& objectPoint = objectPoints[objectPointIndex];
534
535 constexpr Scalar generousSqrProjectionError = Scalar(20 * 20);
536
537 if (Camera::isObjectPointInFrontIF(flippedCamera_T_world, objectPoint) && camera.projectToImageIF(flippedCamera_T_world, objectPoint).sqrDistance(imagePoint) <= generousSqrProjectionError)
538 {
539 bestDistance = distance;
540 bestObjectPointDescriptorIndex = Index32(nObjectPoint);
541 }
542 }
543 }
544
545 if (bestDistance <= maximalDescriptorDistance)
546 {
547 const Index32 objectPointIndex = objectPointIndices[bestObjectPointDescriptorIndex];
548
549 matchedImagePoints.emplace_back(imagePoints[imagePointIndex]);
550 matchedObjectPoints.emplace_back(objectPoints[objectPointIndex]);
551
552 if (useInternalIndices)
553 {
554 internalUsedObjectPointIndices.emplace_back(objectPointIndex);
555 internalUsedImagePointIndices.emplace_back(Index32(imagePointIndex));
556 }
557 }
558 }
559
560 if (matchedImagePoints.size() < size_t(minimalNumberCorrespondences))
561 {
562 world_T_camera.toNull();
563 return false;
564 }
565
566 constexpr unsigned int guidedIterations = 40u;
567
568 world_T_camera.toNull();
569 validIndices.clear();
570 if (Geometry::RANSAC::p3p(camera, ConstArrayAccessor<Vector3>(matchedObjectPoints), ConstArrayAccessor<Vector2>(matchedImagePoints), randomGenerator, world_T_camera, 20u, true, guidedIterations, maximalSqrProjectionError, &validIndices))
571 {
572 if (usedObjectPointIndices != nullptr)
573 {
574 ocean_assert(useInternalIndices);
575
576 usedObjectPointIndices->clear();
577 usedObjectPointIndices->reserve(validIndices.size());
578
579 for (const Index32 validIndex : validIndices)
580 {
581 usedObjectPointIndices->emplace_back(internalUsedObjectPointIndices[validIndex]);
582 }
583 }
584
585 if (usedImagePointIndices != nullptr)
586 {
587 ocean_assert(useInternalIndices);
588
589 usedImagePointIndices->clear();
590 usedImagePointIndices->reserve(validIndices.size());
591
592 for (const Index32 validIndex : validIndices)
593 {
594 usedImagePointIndices->emplace_back(internalUsedImagePointIndices[validIndex]);
595 }
596 }
597
598 return true;
599 }
600 }
601
602 world_T_camera.toNull();
603
604 return false;
605}
606
607template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
608void PoseEstimationT::determineUnguidedBruteForceMatchings(const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPointDescriptors, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePointDescriptors, const TDescriptorDistance maximalDescriptorDistance, Index32* objectPointDescriptorIndices, Worker* worker, TDescriptorDistance* distances)
609{
610 ocean_assert(objectPointDescriptors != nullptr);
611 ocean_assert(imagePointDescriptors != nullptr);
612 ocean_assert(objectPointDescriptorIndices != nullptr);
613
614 if (worker && (numberObjectPointDescriptors >= 1000 || numberImagePointDescriptors >= 1000))
615 {
616 worker->executeFunction(Worker::Function::createStatic(&determineUnguidedBruteForceMatchingsSubset<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>, objectPointDescriptors, numberObjectPointDescriptors, imagePointDescriptors, maximalDescriptorDistance, objectPointDescriptorIndices, distances, 0u, 0u), 0u, (unsigned int)(numberImagePointDescriptors));
617 }
618 else
619 {
620 determineUnguidedBruteForceMatchingsSubset<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>(objectPointDescriptors, numberObjectPointDescriptors, imagePointDescriptors, maximalDescriptorDistance, objectPointDescriptorIndices, distances, 0u, (unsigned int)(numberImagePointDescriptors));
621 }
622}
623
624template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
625void PoseEstimationT::determineGuidedBruteForceMatchings(const AnyCamera& camera, const HomogenousMatrix4& world_T_roughCamera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPoints, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, Index32* objectPointDescriptorIndices, Worker* worker)
626{
627 ocean_assert(camera.isValid());
628 ocean_assert(world_T_roughCamera.isValid());
629 ocean_assert(objectPoints != nullptr);
630 ocean_assert(objectPointDescriptors != nullptr);
631 ocean_assert(imagePoints != nullptr);
632 ocean_assert(imagePointDescriptors != nullptr);
633 ocean_assert(objectPointDescriptorIndices != nullptr);
634 ocean_assert(maximalProjectionError >= 0);
635
636 if (worker && (numberObjectPoints >= 1000 || numberImagePoints >= 1000))
637 {
638 worker->executeFunction(Worker::Function::createStatic(&determineGuidedBruteForceMatchingsSubset<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>, &camera, &world_T_roughCamera, objectPoints, objectPointDescriptors, numberObjectPoints, imagePoints, imagePointDescriptors, maximalDescriptorDistance, maximalProjectionError, objectPointDescriptorIndices, 0u, 0u), 0u, (unsigned int)(numberImagePoints));
639 }
640 else
641 {
642 determineGuidedBruteForceMatchingsSubset<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>(&camera, &world_T_roughCamera, objectPoints, objectPointDescriptors, numberObjectPoints, imagePoints, imagePointDescriptors, maximalDescriptorDistance, maximalProjectionError, objectPointDescriptorIndices, 0u, (unsigned int)(numberImagePoints));
643 }
644}
645
646template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
647void PoseEstimationT::determineUnguidedBruteForceMatchingsSubset(const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPointDescriptors, const TImagePointDescriptor* imagePointDescriptors, const TDescriptorDistance maximalDescriptorDistance, Index32* objectPointDescriptorIndices, TDescriptorDistance* distances, const unsigned int firstImagePointDescriptor, const unsigned int numberImagePointDescriptors)
648{
649 ocean_assert(objectPointDescriptors != nullptr);
650 ocean_assert(imagePointDescriptors != nullptr);
651
652 for (size_t imagePointIndex = size_t(firstImagePointDescriptor); imagePointIndex < size_t(firstImagePointDescriptor + numberImagePointDescriptors); ++imagePointIndex)
653 {
654 const TImagePointDescriptor& imagePointDescriptor = imagePointDescriptors[imagePointIndex];
655
656 TDescriptorDistance bestDistance = NumericT<TDescriptorDistance>::maxValue();
657 Index32 bestObjectPointIndex = Index32(-1);
658
659 for (size_t objectPointIndex = 0; objectPointIndex < numberObjectPointDescriptors; ++objectPointIndex)
660 {
661 const TDescriptorDistance distance = tImageObjectDistanceFunction(imagePointDescriptor, objectPointDescriptors[objectPointIndex]);
662
663 if (distance < bestDistance)
664 {
665 bestDistance = distance;
666 bestObjectPointIndex = Index32(objectPointIndex);
667 }
668 }
669
670 if (bestDistance <= maximalDescriptorDistance)
671 {
672 objectPointDescriptorIndices[imagePointIndex] = bestObjectPointIndex;
673
674 if (distances != nullptr)
675 {
676 distances[imagePointIndex] = bestDistance;
677 }
678 }
679 else
680 {
681 objectPointDescriptorIndices[imagePointIndex] = Index32(-1);
682 }
683 }
684}
685
686template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
687void PoseEstimationT::determineGuidedBruteForceMatchingsSubset(const AnyCamera* camera, const HomogenousMatrix4* world_T_roughCamera, const Vector3* objectPoints, const TObjectPointDescriptor* objectPointDescriptors, const size_t numberObjectPoints, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, Index32* objectPointDescriptorIndices, const unsigned int firstImagePoint, const unsigned int numberImagePoints)
688{
689 ocean_assert(camera != nullptr && camera->isValid());
690 ocean_assert(world_T_roughCamera != nullptr && world_T_roughCamera->isValid());
691 ocean_assert(objectPoints != nullptr);
692 ocean_assert(objectPointDescriptors != nullptr);
693 ocean_assert(imagePoints != nullptr);
694 ocean_assert(imagePointDescriptors != nullptr);
695 ocean_assert(maximalProjectionError >= 0);
696
697 const Scalar maximalSqrProjectionError = Numeric::sqr(maximalProjectionError);
698
699 const HomogenousMatrix4 flippedCamera_T_world(AnyCamera::standard2InvertedFlipped(*world_T_roughCamera));
700
701 for (size_t imagePointIndex = size_t(firstImagePoint); imagePointIndex < size_t(firstImagePoint + numberImagePoints); ++imagePointIndex)
702 {
703 const Vector2& imagePoint = imagePoints[imagePointIndex];
704 ocean_assert(camera->isInside(imagePoint));
705
706 const TImagePointDescriptor& imagePointDescriptor = imagePointDescriptors[imagePointIndex];
707
708 TDescriptorDistance bestDistance = NumericT<TDescriptorDistance>::maxValue();
709 Index32 bestObjectPointIndex = Index32(-1);
710
711 for (size_t objectPointIndex = 0; objectPointIndex < numberObjectPoints; ++objectPointIndex)
712 {
713 const TDescriptorDistance distance = tImageObjectDistanceFunction(imagePointDescriptor, objectPointDescriptors[objectPointIndex]);
714
715 if (distance < bestDistance)
716 {
717 const Vector3& objectPoint = objectPoints[objectPointIndex];
718
719 if (Camera::isObjectPointInFrontIF(flippedCamera_T_world, objectPoint) && camera->projectToImageIF(flippedCamera_T_world, objectPoint).sqrDistance(imagePoint) <= maximalSqrProjectionError)
720 {
721 bestDistance = distance;
722 bestObjectPointIndex = Index32(objectPointIndex);
723 }
724 }
725 }
726
727 if (bestDistance <= maximalDescriptorDistance)
728 {
729 objectPointDescriptorIndices[imagePointIndex] = bestObjectPointIndex;
730 }
731 else
732 {
733 objectPointDescriptorIndices[imagePointIndex] = Index32(-1);
734 }
735 }
736}
737
738template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
739void PoseEstimationT::determineGuidedMatchings(const AnyCamera& camera, const HomogenousMatrix4& world_T_camera, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const size_t numberImagePoints, const Vector3* objectPoints, const Geometry::Octree& objectPointOctree, const Index32* objectPointIds, const UnorderedDescriptorMap<TObjectPointDescriptor>& objectPointDescriptorMap, Vectors2& matchedImagePoints, Vectors3& matchedObjectPoints, const TDescriptorDistance maximalDescriptorDistance, Indices32* matchedImagePointIndices, Indices32* matchedObjectPointIds, Worker* worker)
740{
741 ocean_assert(camera.isValid() && world_T_camera.isValid());
742 ocean_assert(imagePoints != nullptr && imagePointDescriptors != nullptr && numberImagePoints >= 1);
743 ocean_assert(objectPoints != nullptr && objectPointIds != nullptr);
744
745 ocean_assert(matchedImagePoints.empty());
746 ocean_assert(matchedObjectPoints.empty());
747
748 if (matchedObjectPointIds != nullptr)
749 {
750 matchedObjectPointIds->clear();
751 }
752
753 if (matchedImagePointIndices != nullptr)
754 {
755 matchedImagePointIndices->clear();
756 }
757
758 if (worker != nullptr)
759 {
760 Lock lock;
761 worker->executeFunction(Worker::Function::createStatic(&PoseEstimationT::determineGuidedMatchingsSubset<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>, &camera, &world_T_camera, imagePoints, imagePointDescriptors, objectPoints, &objectPointOctree, objectPointIds, &objectPointDescriptorMap, &matchedImagePoints, &matchedObjectPoints, matchedImagePointIndices, matchedObjectPointIds, maximalDescriptorDistance, &lock, 0u, 0u), 0u, (unsigned int)(numberImagePoints));
762 }
763 else
764 {
765 determineGuidedMatchingsSubset<TImagePointDescriptor, TObjectPointDescriptor, TDescriptorDistance, tImageObjectDistanceFunction>(&camera, &world_T_camera, imagePoints, imagePointDescriptors, objectPoints, &objectPointOctree, objectPointIds, &objectPointDescriptorMap, &matchedImagePoints, &matchedObjectPoints, matchedImagePointIndices, matchedObjectPointIds, maximalDescriptorDistance, nullptr, 0u, (unsigned int)(numberImagePoints));
766 }
767}
768
769template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
770std::vector<TDescriptorDistance> PoseEstimationT::determineDescriptorDistances(const TObjectPointDescriptor* objectPointDescriptors, const TImagePointDescriptor* imagePointDescriptors, const Index32* objectPointDescriptorIndices, const Index32* imagePointDescriptorIndices, const size_t numberCorrespondences)
771{
772 ocean_assert(objectPointDescriptors != nullptr);
773 ocean_assert(imagePointDescriptors != nullptr);
774 ocean_assert(objectPointDescriptorIndices != nullptr);
775 ocean_assert(imagePointDescriptorIndices != nullptr);
776 ocean_assert(numberCorrespondences >= 1);
777
778 std::vector<TDescriptorDistance> result;
779 result.reserve(numberCorrespondences);
780
781 for (size_t n = 0; n < numberCorrespondences; ++n)
782 {
783 const Index32& objectPointDescriptorIndex = objectPointDescriptorIndices[n];
784 const Index32& imagePointDescriptorIndex = imagePointDescriptorIndices[n];
785
786 result.emplace_back(tImageObjectDistanceFunction(imagePointDescriptors[imagePointDescriptorIndex], objectPointDescriptors[objectPointDescriptorIndex]));
787 }
788
789 return result;
790}
791
792template <typename TImagePointDescriptor, typename TObjectPointDescriptor, typename TDescriptorDistance, TDescriptorDistance(*tImageObjectDistanceFunction)(const TImagePointDescriptor&, const TObjectPointDescriptor&)>
793void PoseEstimationT::determineGuidedMatchingsSubset(const AnyCamera* camera, const HomogenousMatrix4* world_T_camera, const Vector2* imagePoints, const TImagePointDescriptor* imagePointDescriptors, const Vector3* objectPoints, const Geometry::Octree* objectPointOctree, const Index32* objectPointIds, const UnorderedDescriptorMap<TObjectPointDescriptor>* objectPointDescriptorMap, Vectors2* matchedImagePoints, Vectors3* matchedObjectPoints, Indices32* matchedImagePointIndices, Indices32* matchedObjectPointIds, const TDescriptorDistance maximalDescriptorDistance, Lock* lock, const unsigned int firstImagePoint, const unsigned int numberImagePoints)
794{
795 static_assert(tImageObjectDistanceFunction != nullptr);
796
797 ocean_assert(camera != nullptr && camera->isValid());
798 ocean_assert(world_T_camera && world_T_camera->isValid());
799
800 ocean_assert(imagePoints != nullptr && imagePointDescriptors != nullptr && objectPoints != nullptr);
801 ocean_assert(objectPointOctree != nullptr && objectPointIds != nullptr && objectPointDescriptorMap != nullptr);
802
803 ocean_assert(matchedImagePoints != nullptr);
804 ocean_assert(matchedObjectPoints != nullptr);
805
806 Vectors2 localMatchedImagePoints;
807 Vectors3 localMatchedObjectPoints;
808 Indices32 localMatchedImagePointIndices;
809 Indices32 localMatchedObjectPointIds;
810
811 localMatchedImagePoints.reserve(numberImagePoints);
812 localMatchedObjectPoints.reserve(numberImagePoints);
813 localMatchedImagePointIndices.reserve(numberImagePoints);
814 localMatchedObjectPointIds.reserve(numberImagePoints);
815
816 const HomogenousMatrix4 flippedCamera_T_world(Camera::standard2InvertedFlipped(*world_T_camera));
817
818 const Scalar tanHalfAngle = Numeric::tan(Numeric::deg2rad(Scalar(0.2)));
819
820 std::vector<const Indices32*> leaves;
821 leaves.reserve(32);
822
823 constexpr Scalar generousSqrProjectionError = Scalar(20 * 20);
824
825 Geometry::Octree::ReusableData reusableData;
826
827 for (unsigned int nImagePoint = firstImagePoint; nImagePoint < firstImagePoint + numberImagePoints; ++nImagePoint)
828 {
829 const Vector2& imagePoint = imagePoints[nImagePoint];
830 ocean_assert(camera->isInside(imagePoint));
831
832 const TImagePointDescriptor& imagePointDescriptor = imagePointDescriptors[nImagePoint];
833
834 const Line3 ray = camera->ray(imagePoint, *world_T_camera);
835
836 leaves.clear();
837 objectPointOctree->intersectingLeaves(ray, tanHalfAngle, leaves, reusableData);
838
839 TDescriptorDistance bestDistance = NumericT<TDescriptorDistance>::maxValue();
840 Index32 bestObjectPointIndex = Index32(-1);
841
842 for (const Indices32* leaf : leaves)
843 {
844 for (const Index32& objectPointIndex : *leaf)
845 {
846 const Vector3& objectPoint = objectPoints[objectPointIndex];
847
848 if (Camera::isObjectPointInFrontIF(flippedCamera_T_world, objectPoint) && camera->projectToImageIF(flippedCamera_T_world, objectPoint).sqrDistance(imagePoint) <= generousSqrProjectionError)
849 {
850 const Index32 objectPointId = objectPointIds[objectPointIndex];
851 const typename UnorderedDescriptorMap<TObjectPointDescriptor>::const_iterator iObjectPointDescriptor = objectPointDescriptorMap->find(objectPointId);
852 ocean_assert(iObjectPointDescriptor != objectPointDescriptorMap->cend());
853
854 const TDescriptorDistance distance = tImageObjectDistanceFunction(imagePointDescriptor, iObjectPointDescriptor->second);
855
856 if (distance < bestDistance)
857 {
858 bestDistance = distance;
859 bestObjectPointIndex = objectPointIndex;
860 }
861 }
862 }
863 }
864
865 if (bestDistance <= maximalDescriptorDistance)
866 {
867 ocean_assert(bestObjectPointIndex != Index32(-1));
868
869 localMatchedImagePoints.emplace_back(imagePoint);
870 localMatchedObjectPoints.emplace_back(objectPoints[bestObjectPointIndex]);
871
872 localMatchedImagePointIndices.emplace_back(nImagePoint);
873 localMatchedObjectPointIds.emplace_back(objectPointIds[bestObjectPointIndex]);
874 }
875 }
876
877 const OptionalScopedLock scopedLock(lock);
878
879 matchedImagePoints->insert(matchedImagePoints->cend(), localMatchedImagePoints.cbegin(), localMatchedImagePoints.cend());
880 matchedObjectPoints->insert(matchedObjectPoints->cend(), localMatchedObjectPoints.cbegin(), localMatchedObjectPoints.cend());
881
882 if (matchedImagePointIndices != nullptr)
883 {
884 matchedImagePointIndices->insert(matchedImagePointIndices->cend(), localMatchedImagePointIndices.cbegin(), localMatchedImagePointIndices.cend());
885 }
886
887 if (matchedObjectPointIds != nullptr)
888 {
889 matchedObjectPointIds->insert(matchedObjectPointIds->cend(), localMatchedObjectPointIds.cbegin(), localMatchedObjectPointIds.cend());
890 }
891}
892
893}
894
895}
896
897#endif // META_OCEAN_TRACKING_POSE_ESTIMATION_T_H
This class implements the abstract base class for all AnyCamera objects.
Definition AnyCamera.h:131
virtual VectorT2< T > projectToImageIF(const VectorT3< T > &objectPoint) const =0
Projects a 3D object point into the camera frame.
virtual bool isValid() const =0
Returns whether this camera is valid.
virtual LineT3< T > ray(const VectorT2< T > &distortedImagePoint, const HomogenousMatrixT4< T > &world_T_camera) const =0
Returns a ray starting at the camera's center and intersecting a given 2D point in the image.
virtual bool isInside(const VectorT2< T > &imagePoint, const T signedBorder=T(0)) const =0
Returns whether a given 2D image point lies inside the camera frame.
static Caller< void > createStatic(typename StaticFunctionPointerMaker< void, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass, NullClass >::Type function)
Creates a new caller container for a static function with no function parameter.
Definition Caller.h:2877
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:778
static bool isObjectPointInFrontIF(const HomogenousMatrixT4< Scalar > &flippedCamera_T_world, const VectorT3< Scalar > &objectPoint, const Scalar epsilon=NumericT< Scalar >::eps())
Determines whether a given 3D object point lies in front of a camera while the location of the camera...
Definition Camera.h:855
This class implements an accessor providing direct access to a constant array of elements.
Definition Accessor.h:400
This class implements a container allowing to define gravity constraints during e....
Definition GravityConstraints.h:63
static bool p3p(const AnyCamera &anyCamera, const ConstIndexedAccessor< Vector3 > &objectPointAccessor, const ConstIndexedAccessor< Vector2 > &imagePointAccessor, RandomGenerator &randomGenerator, HomogenousMatrix4 &world_T_camera, const unsigned int minimalValidCorrespondences=5u, const bool refine=true, const unsigned int iterations=20u, const Scalar sqrPixelErrorThreshold=Scalar(5 *5), Indices32 *usedIndices=nullptr, Scalar *sqrAccuracy=nullptr, const GravityConstraints *gravityConstraints=nullptr)
Calculates a pose using the perspective pose problem with three point correspondences using any camer...
static unsigned int iterations(const unsigned int model, const Scalar successProbability=Scalar(0.99), const Scalar faultyRate=Scalar(0.2), const unsigned int maximalIterations=1000000u)
Calculates the number of iterations necessary to find an outlier-free model data set.
void toNull()
Sets the matrix to a zero matrix (including the lower right element).
Definition HomogenousMatrix4.h:1795
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:68
This class implements a recursive lock object.
Definition Lock.h:31
static constexpr T deg2rad(const T deg)
Converts deg to rad.
Definition Numeric.h:3241
static T tan(const T value)
Returns the tangent of a given value.
Definition Numeric.h:1604
static constexpr T sqr(const T value)
Returns the square of a given value.
Definition Numeric.h:1499
static constexpr T maxValue()
Returns the max scalar value.
Definition Numeric.h:3253
This class implements an optional recursive scoped lock object locking the lock object only if it's d...
Definition Lock.h:387
This class implements a generator for random numbers.
Definition RandomGenerator.h:42
This class implements functions to estimate camera poses using template-based data types.
Definition PoseEstimationT.h:36
static void determineGuidedBruteForceMatchings(const AnyCamera &camera, const HomogenousMatrix4 &world_T_roughCamera, const Vector3 *objectPoints, const TObjectPointDescriptor *objectPointDescriptors, const size_t numberObjectPoints, const Vector2 *imagePoints, const TImagePointDescriptor *imagePointDescriptors, const size_t numberImagePoints, TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, Index32 *objectPointDescriptorIndices, Worker *worker)
Determines the guided matching (with known rough camera pose) between image point and object point fe...
Definition PoseEstimationT.h:625
static void determineGuidedBruteForceMatchingsSubset(const AnyCamera *camera, const HomogenousMatrix4 *world_T_roughCamera, const Vector3 *objectPoints, const TObjectPointDescriptor *objectPointDescriptors, const size_t numberObjectPoints, const Vector2 *imagePoints, const TImagePointDescriptor *imagePointDescriptors, TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, Index32 *objectPointDescriptorIndices, const unsigned int firstImagePoint, const unsigned int numberImagePoints)
Determines the guided matching (without known rough camera pose) between a subset of image point and ...
Definition PoseEstimationT.h:687
static bool determinePoseBruteForce(const AnyCamera &camera, const Vector3 *objectPoints, const TObjectPointDescriptor *objectPointDescriptors, const size_t numberObjectPoints, const Vector2 *imagePoints, const TImagePointDescriptor *imagePointDescriptors, const size_t numberImagePoints, RandomGenerator &randomGenerator, HomogenousMatrix4 &world_T_camera, const unsigned int minimalNumberCorrespondences, const TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate=Scalar(0.15), Indices32 *usedObjectPointIndices=nullptr, Indices32 *usedImagePointIndices=nullptr, const HomogenousMatrix4 &world_T_roughCamera=HomogenousMatrix4(false), Worker *worker=nullptr, const Geometry::GravityConstraints *gravityConstraints=nullptr)
Determines the 6-DOF pose for 2D/3D correspondences applying a brute-force search.
Definition PoseEstimationT.h:260
static void determineGuidedMatchingsSubset(const AnyCamera *camera, const HomogenousMatrix4 *world_T_camera, const Vector2 *imagePoints, const TImagePointDescriptor *imagePointDescriptors, const Vector3 *objectPoints, const Geometry::Octree *objectPointOctree, const Index32 *objectPointIds, const UnorderedDescriptorMap< TObjectPointDescriptor > *objectPointDescriptorMap, Vectors2 *matchedImagePoints, Vectors3 *matchedObjectPoints, Indices32 *matchedImagePointIndices, Indices32 *matchedObjectPointIds, const TDescriptorDistance maximalDescriptorDistance, Lock *lock, const unsigned int firstImagePoint, const unsigned int numberImagePoints)
Determines the guided matching between 2D/3D correspondences for a subset of the given 2D image point...
Definition PoseEstimationT.h:793
static std::vector< TDescriptorDistance > determineDescriptorDistances(const TObjectPointDescriptor *objectPointDescriptors, const TImagePointDescriptor *imagePointDescriptors, const Index32 *objectPointDescriptorIndices, const Index32 *imagePointDescriptorIndices, const size_t numberCorrespondences)
Returns the individual descriptor distances for a given set of corresponding feature descriptor pairs...
Definition PoseEstimationT.h:770
std::unordered_map< Index32, TDescriptor > UnorderedDescriptorMap
Definition of an unordered map mapping object point ids to descriptors.
Definition PoseEstimationT.h:43
static void determineUnguidedBruteForceMatchings(const TObjectPointDescriptor *objectPointDescriptors, const size_t numberObjectPointDescriptors, const TImagePointDescriptor *imagePointDescriptors, const size_t numberImagePointDescriptors, TDescriptorDistance maximalDescriptorDistance, Index32 *objectPointDescriptorIndices, Worker *worker, TDescriptorDistance *distances=nullptr)
Determines the unguided matching (without apriori information) between image point and object point f...
Definition PoseEstimationT.h:608
static void determineUnguidedBruteForceMatchingsSubset(const TObjectPointDescriptor *objectPointDescriptors, const size_t numberObjectPointDescriptors, const TImagePointDescriptor *imagePointDescriptors, TDescriptorDistance maximalDescriptorDistance, Index32 *objectPointDescriptorIndices, TDescriptorDistance *distances, const unsigned int firstImagePointDescriptor, const unsigned int numberImagePointDescriptors)
Determines the unguided matching between a subset of image point and object point features applying a...
Definition PoseEstimationT.h:647
static bool determinePoseBruteForceWithArbitraryDescriptorOrder(const AnyCamera &camera, const Vector3 *objectPoints, const TObjectPointDescriptor *objectPointDescriptors, const Index32 *objectPointIndices, const size_t numberObjectDescriptors, const Vector2 *imagePoints, const TImagePointDescriptor *imagePointDescriptors, const size_t numberImagePoints, RandomGenerator &randomGenerator, HomogenousMatrix4 &world_T_camera, const unsigned int minimalNumberCorrespondences, const TDescriptorDistance maximalDescriptorDistance, const Scalar maximalProjectionError, const Scalar inlierRate=Scalar(0.15), Indices32 *usedObjectPointIndices=nullptr, Indices32 *usedImagePointIndices=nullptr, const HomogenousMatrix4 &world_T_roughCamera=HomogenousMatrix4(false))
Determines the 6-DOF pose for 2D/3D correspondences applying a brute-force search.
Definition PoseEstimationT.h:428
static void determineGuidedMatchings(const AnyCamera &camera, const HomogenousMatrix4 &world_T_camera, const Vector2 *imagePoints, const TImagePointDescriptor *imagePointDescriptors, const size_t numberImagePoints, const Vector3 *objectPoints, const Geometry::Octree &objectPointOctree, const Index32 *objectPointIds, const UnorderedDescriptorMap< TObjectPointDescriptor > &objectPointDescriptorMap, Vectors2 &matchedImagePoints, Vectors3 &matchedObjectPoints, const TDescriptorDistance maximalDescriptorDistance, Indices32 *matchedImagePointIndices=nullptr, Indices32 *matchedObjectPointIds=nullptr, Worker *worker=nullptr)
Determines the guided matching between 2D/3D correspondences.
Definition PoseEstimationT.h:739
static size_t countBijectiveCorrespondences(const Index32 *usedPointIndices, const size_t size)
Counts the number of bijective correspondences based on provided indices of used points (either image...
static void removeNonBijectiveCorrespondences(const AnyCamera &camera, const HomogenousMatrix4 &world_T_camera, const Vector3 *objectPoints, const Vector2 *imagePoints, Indices32 &objectPointIndices, Indices32 &imagePointIndices, const bool checkImagePoints)
Removes non-bijective correspondences from 2D/3D correspondences.
This class implements a worker able to distribute function calls over different threads.
Definition Worker.h:33
bool executeFunction(const Function &function, const unsigned int first, const unsigned int size, const unsigned int firstIndex=(unsigned int)(-1), const unsigned int sizeIndex=(unsigned int)(-1), const unsigned int minimalIterations=1u, const unsigned int threadIndex=(unsigned int)(-1))
Executes a callback function separable by two function parameters.
std::vector< Index32 > Indices32
Definition of a vector holding 32 bit index values.
Definition Base.h:96
uint32_t Index32
Definition of a 32 bit index value.
Definition Base.h:84
std::unordered_set< Index32 > UnorderedIndexSet32
Definition of an unordered_set holding 32 bit indices.
Definition Base.h:126
OctreeT< Scalar > Octree
Definition of an Octree using Scalar as data type.
Definition Octree.h:32
std::vector< Vector2 > Vectors2
Definition of a vector holding Vector2 objects.
Definition Vector2.h:64
float Scalar
Definition of a scalar type.
Definition Math.h:129
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