Ocean
SLAMTracker.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_OFFLINE_SLAM_TRACKER_H
9 #define META_OCEAN_TRACKING_OFFLINE_SLAM_TRACKER_H
10 
14 
16 #include "ocean/base/Scheduler.h"
17 
19 
21 #include "ocean/tracking/Solver3.h"
22 
23 namespace Ocean
24 {
25 
26 namespace Tracking
27 {
28 
29 namespace Offline
30 {
31 
32 // Forward declaration.
33 class SLAMTracker;
34 
35 /**
36  * Definition of an object reference holding a PlanarRectangleTracker object.
37  * @see PlanarRectangleTracker.
38  * @ingroup trackingoffline
39  */
41 
42 /**
43  * This class implements a SLAM (Simultaneous Localization and Mapping) tracker for arbitrary environments and camera movements.
44  * The tracker determines camera poses and the location of 3D object points concurrently only due to the positions of corresponding image points in individual camera frames.<br>
45  * The tracker mainly extracts all necessary information from a database providing valid image point positions and a valid topology between image points, object points and camera poses.<br>
46  * However, neither the locations of the 3D object points nor the camera poses are necessary for this tracker.
47  * @ingroup trackingoffline
48  */
49 class OCEAN_TRACKING_OFFLINE_EXPORT SLAMTracker : public FrameTracker
50 {
51  public:
52 
53  /**
54  * Definition of a map mapping frame indices to transformations e.g., camera poses or object transformations.
55  */
56  typedef std::map<unsigned int, HomogenousMatrix4> TransformationMap;
57 
58  protected:
59 
60  /**
61  * This class implements a pair of thresholds.
62  */
64  {
65  public:
66 
67  /**
68  * Creates a new pair object.
69  * @param maximalCosine The maximal cosine value for an object point, with range (0, 1)
70  * @param minimalObservationRatio The minimal number of frames in which an object point must be visible, defined as ratio of an external frame range, with range (0, 1]
71  */
72  inline ReliabilityPair(const Scalar maximalCosine, const Scalar minimalObservationRatio);
73 
74  /**
75  * Returns the maximal cosine value.
76  * @return Maximal cosine value
77  */
78  inline Scalar maximalCosine() const;
79 
80  /**
81  * Returns the minimal observation ratio.
82  * @return Observation ratio
83  */
84  inline Scalar minimalObservationRatio() const;
85 
86  /**
87  * Returns the minimal number of observations in relation to a given number of maximal possible observations.
88  * @param overallObservation The maximal possible number of observation
89  * @return max(min(tLowerBoundary, overallObservation), overallObservation * ratio)
90  * @tparam tLowerBoundary Explicit lower boundary
91  */
92  template <unsigned int tLowerBoundary>
93  inline unsigned int minimalObservations(const unsigned int overallObservation) const;
94 
95  protected:
96 
97  /// The maximal cosine value.
98  const Scalar maximalCosineValue_ = Scalar(0);
99 
100  /// The minimal observation ratio.
101  const Scalar minimalObservationRatio_ = Scalar(0);
102  };
103 
104  public:
105 
106  /**
107  * Creates a new SLAM Tracker object.
108  */
109  SLAMTracker() = default;
110 
111  /**
112  * Destructs a SLAM Tracker object.
113  */
114  ~SLAMTracker() override;
115 
116  /**
117  * Starts the offline tracker.
118  * @see OfflineTracker::start().
119  */
120  bool start() override;
121 
122  /**
123  * Stops the offline tracker.
124  * @see OfflineTracker::stop().
125  */
126  bool stop(const unsigned int timeout = 0u) override;
127 
128  /**
129  * Returns the tracking quality of this tracker.
130  * @return The tracker's quality, TQ_AUTOMATIC by default
131  */
133 
134  /**
135  * Returns the used-defined horizontal field of view of the camera.
136  * @return The horizontal field of view that explicitly has been set, in radian with range (0, PI), -1 if the field of view is not known, -1 by default
137  */
138  virtual Scalar cameraFieldOfView() const;
139 
140  /**
141  * Returns the camera profile optimization strategy of this tracker.
142  * @return The tracker's optimization strategy for the camera profile, OS_INTRINSIC_PARAMETERS_DISTORTIONS by default
143  */
145 
146  /**
147  * Returns the abstract motion type of this tracker.
148  * @return The tracker's abstract motion type
149  */
151 
152  /**
153  * Returns the motion speed of this tracker (the speed of the visual information in the frames on which the tracker relies).
154  * @return The tracker's motion speed
155  */
157 
158  /**
159  * Returns the specific region of interest which covers image content in the start frame of this tracker.
160  * @return The tracker's region of interest
161  */
162  inline const CV::SubRegion& regionOfInterest() const;
163 
164  /**
165  * Sets the tracking quality of the tracker.
166  * The quality must be set before the tracker starts.
167  * @param trackingQuality The quality that specifies the performance/accuracy of the tracker.
168  * @return True, if succeeded
169  */
170  virtual bool setTrackingQuality(const TrackingQuality trackingQuality);
171 
172  /**
173  * Sets the optimization strategy for the camera profile of this tracker.
174  * The strategy must be set before the tracker starts.
175  * @param optimizationStrategy The optimization strategy to set
176  * @return True, if succeeded
177  */
178  virtual bool setCameraOptimizationStrategy(const PinholeCamera::OptimizationStrategy optimizationStrategy);
179 
180  /**
181  * Explicitly sets the horizontal field of view of the camera.
182  * The field of view must be set before the tracker starts.
183  * @param fovX The horizontal field of view that will be used by the tracker, in radian with range (0, PI), -1 if the field of view is not known
184  * @return True, if succeeded
185  */
186  virtual bool setCameraFieldOfView(const Scalar fovX);
187 
188  /**
189  * Sets the abstract motion type of this tracker, if known before that tracker starts.
190  * The motion type must be set before the tracker starts.
191  * @param abstractMotionType The abstract motion type to set
192  * @return True, if succeeded
193  */
194  virtual bool setAbstractMotionType(const AbstractMotionType abstractMotionType);
195 
196  /**
197  * Sets the motion speed of this tracker.
198  * The motion speed must be set before the tracker starts.
199  * @return motionSpeed The motion speed to set
200  * @return True, if succeeded
201  */
202  virtual bool setMotionSpeed(const PointPaths::MotionSpeed motionSpeed);
203 
204  /**
205  * Sets a specific region of interest which covers image content in the start frame of this tracker.
206  * The roi cannot be set if the tracker is active
207  * @param regionOfInterest The region of interest to set, an invalid roi removes an already existing one
208  * @param soleApplication True, if the tracker uses only the region of interest and not the remaining frame information for tracking
209  * @return True, if succeeded
210  * @see setTrackingFrameRange(), setFrameProviderInterface().
211  */
212  bool setRegionOfInterest(const CV::SubRegion& regionOfInterest, const bool soleApplication);
213 
214  /**
215  * Extracts the poses from this tracker for a specified frame range not considering any specific region of interest.
216  * Beware: The tracker must have finished before calling this function!<br>
217  * @param lowerFrameIndex The index of the lower frame, with range [0, infinity)
218  * @param upperFrameIndex The index of the upper frame, with range [lowerFrameIndex, infinity)
219  * @param offlinePoses The resulting poses for the specified frame range, not existing poses will be invalid
220  * @param minimalCorrespondences The number of minimal valid 2D/3D point correspondences so that a pose will be provided
221  * @param estimator The robust estimator which is applied for the non-linear pose optimization
222  * @param minimalValidCorrespondenceRatio The ratio of the minimal number of valid correspondences (the valid correspondences will be determined from a RANSAC iteration), with range [0, 1]
223  * @param ransacMaximalSqrError The maximal squared pixel error between image point and projected object points for RANSAC iterations, with range (0, infinity)
224  * @param maximalRobustError The maximal average robust pixel error between image point and projected object points so that a pose counts as valid, with range (0, infinity)
225  * @param finalAverageError Optional resulting average final error for all valid poses, the error depends on the selected robust estimator
226  * @param worker Optional worker object to distribute the computation
227  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
228  * @return True, if all poses have been determined (some poses may be invalid)
229  */
230  bool extractPoses(const unsigned int lowerFrameIndex, const unsigned int upperFrameIndex, OfflinePoses& offlinePoses, const unsigned int minimalCorrespondences = 5u, const Geometry::Estimator::EstimatorType estimator = Geometry::Estimator::ET_SQUARE, const Scalar minimalValidCorrespondenceRatio = Scalar(1), const Scalar ransacMaximalSqrError = Scalar(3.5 * 3.5), const Scalar maximalRobustError = Scalar(3.5 * 3.5), Scalar* finalAverageError = nullptr, Worker* worker = nullptr, bool* abort = nullptr) const;
231 
232  /**
233  * Extracts the poses from this tracker for a specific region of interest.
234  * The region of interest must cover a planar area (a plane).<br>
235  * Beware: The tracker must have finished before calling this function!<br>
236  * @param lowerFrameIndex The index of the lower frame, with range [0, infinity)
237  * @param regionOfInterestFrameIndex The index of the frame in which the region of interest is defined, with range [lowerFrameIndex, upperFrameIndex]
238  * @param upperFrameIndex The index of the upper frame, with range [lowerFrameIndex, infinity)
239  * @param regionOfInterest The region of interest for which the resulting poses will be optimized
240  * @param offlinePoses The resulting poses for the specified frame range, not existing poses will be invalid
241  * @param planeTransformation The resulting transformation of the plane representing the geometry for the region of interest, with z-axis defining the normal of the plane
242  * @param minimalCorrespondences The minimal number of valid 2D/3D point correspondences so that a pose will be provided, with range [3, infinity)
243  * @param minimalKeyFrames The minimal number of key frames that will be applied to optimized the object points located in the region of interest, with range [2, infinity)
244  * @param estimator The robust estimator which is applied for the non-linear pose optimization
245  * @param minimalValidCorrespondenceRatio The ratio of the minimal number of valid correspondences (the valid correspondences will be determined from a RANSAC iteration), with range [0, 1]
246  * @param ransacMaximalSqrError The maximal squared pixel error between image point and projected object points for RANSAC iterations, with range (0, infinity)
247  * @param maximalRobustError The maximal average robust pixel error between image point and projected object points so that a pose counts as valid, with range (0, infinity)
248  * @param finalAverageError Optional resulting average final error for all valid poses, the error depends on the selected robust estimator
249  * @param worker Optional worker object to distribute the computation
250  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
251  * @return True, if all poses have been determined (some poses may be invalid)
252  */
253  bool extractPoses(const unsigned int lowerFrameIndex, const unsigned int regionOfInterestFrameIndex, const unsigned int upperFrameIndex, const CV::SubRegion& regionOfInterest, OfflinePoses& offlinePoses, HomogenousMatrix4& planeTransformation, const unsigned int minimalCorrespondences = 5u, const unsigned int minimalKeyFrames = 50u, const Geometry::Estimator::EstimatorType estimator = Geometry::Estimator::ET_SQUARE, const Scalar minimalValidCorrespondenceRatio = Scalar(1), const Scalar ransacMaximalSqrError = Scalar(3.5 * 3.5), const Scalar maximalRobustError = Scalar(3.5 * 3.5), Scalar* finalAverageError = nullptr, Worker* worker = nullptr, bool* abort = nullptr) const;
254 
255  /**
256  * Determines the location of some initial 3D object points which are all visible within a defined frame range (range of camera frame without known camera pose values).
257  * The accuracy and reliability of the resulting initial 3D object points can vary due to the given database (which is based on camera motions etc.).<br>
258  * Thus, initial object point locations should never be used directly, instead the locations should be verified or stabilized etc.<br>
259  * This function is based on a database providing image points (projections of the 3D object points) for several camera frames.<br>
260  * The database must provide valid image point positions and the topology between the image points and their corresponding object points and their observation information (visibility of object points in individual camera frames/poses).<br>
261  * This functions tries to add initial information regarding some 3D object point locations and some camera pose values.<br>
262  * The given database will be modified so that the database finally stores the information determined by this function.<br>
263  * The origin of all image points provided by the database must be the upper left frame corner.<br>
264  * This functions has the capability to identify/separate static and dynamic 3D object points and relies only on static object points for initial pose calculations.<br>
265  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
266  * @param database The database providing only the image point positions and the topology information, not the 3D object point locations and not the camera pose values
267  * @param randomGenerator A random generator object
268  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
269  * @param startFrame Optional index of the start frame from which the object point determination starts, with range [lowerFrame, upperFrame], otherwise nullptr
270  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
271  * @param regionOfInterest Optional region of interest defining a specific area in the start frame so that the object points lying in the region are handled with higher priority, an invalid region to avoid any special region of interest handling, a valid region needs a valid start frame
272  * @param soleRegionOfInterest True, if the tracking must rely on the region of interest only and if no remaining information must be used
273  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
274  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
275  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
276  * @param progress Optional resulting progress with range [0, 1]
277  * @return True, if at least one initial 3D object point and one camera pose could be determined
278  * @see extendInitialObjectPoints().
279  */
280  static bool determineInitialObjectPoints(const PinholeCamera& pinholeCamera, Database& database, RandomGenerator& randomGenerator, const unsigned int lowerFrame, const unsigned int* startFrame, const unsigned int upperFrame, const CV::SubRegion& regionOfInterest, const bool soleRegionOfInterest, unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
281 
282  /**
283  * Determines the locations of further (stable and reliable) 3D object points which are visible within a defined frame range and for which the 3D location is not known yet.
284  * Thus, this function extends a set of already known 3D object point locations with locations of further 3D object points which are predicted to be very reliable.<br>
285  * The number of new object point locations can vary but in general will be not very large as in this step the concentration lies on quality rather than quantity.<br>
286  * The given database must provide locations of some already known 3D object points and further the camera pose values for some camera frames (within the defined frame range) in which the 3D object points are visible.<br>
287  * The database will be modified as the database will receive the locations of new 3D object points and camera pose values.<br>
288  * If this functions succeeds the database will hold reliable and stable 3D object point locations and a set of valid camera pose values.<br>
289  * Thus, the database will provide reliable information within the defined frame range.
290  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
291  * @param database The database providing the image point positions, the topology information and some 3D object point locations and camera pose values
292  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
293  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
294  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
295  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
296  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
297  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
298  * @return True, if at least one 3D object point location and one camera pose are finally in the database
299  * @see extendStableObjectPoints(), determineInitialObjectPoints().
300  */
301  static bool extendInitialObjectPoints(const PinholeCamera& pinholeCamera, Database& database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr);
302 
303  /**
304  * Optimizes the camera profile for a database with stable initial object points.
305  * Beware: Do not optimize the camera profile 'too early', the database must hold enough object point locations and camera poses so that the true camera profile can be determined.
306  * @param pinholeCamera The pinhole camera profile to be optimized
307  * @param database The database providing locations of initial but stable object points (with corresponding valid camera poses)
308  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
309  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
310  * @param findInitialFieldOfView True, to apply a determination of the initial field of view of the camera (should be done if the camera's field of view is not known)
311  * @param optimizationStrategy The optimization strategy for the camera parameters which will be applied, OS_INVALID to avoid any optimization of the camera parameters
312  * @param maximalKeyFrames The maximal number of key frames that are used to optimize the profile of the camera, the higher the number the better the final accuracy but the longer the optimization will take, with range [1, upperFrame - lowerFrame + 1u]
313  * @param optimizedCamera The optimized camera profile
314  * @param optimizedDatabase The database with new object points and camera poses matching to the new camera profile
315  * @param cameraMotion Optional resulting motion of the camera that could be identified during the optimization of the camera profile, CM_UNKNOWN if the motion could not be determined
316  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
317  * @param finalMeanSqrError Optional resulting final mean squared projection error for the optimized camera profile
318  * @return True, if the camera profile could be optimized or changed due to the specified properties; False, if neither the camera profile nor the database has been modified so that the caller should use the initial camera profile and database for further calculations
319  */
320  static bool optimizeCamera(const PinholeCamera& pinholeCamera, const Database& database, const unsigned int lowerFrame, const unsigned int upperFrame, const bool findInitialFieldOfView, const PinholeCamera::OptimizationStrategy optimizationStrategy, const unsigned int maximalKeyFrames, PinholeCamera& optimizedCamera, Database& optimizedDatabase, Solver3::CameraMotion* cameraMotion = nullptr, bool* abort = nullptr, Scalar* finalMeanSqrError = nullptr);
321 
322  /**
323  * This function extends a database providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
324  * The resulting database will provide as much stable 3D object point location as necessary (if possible) to guarantee stable poses.<br>
325  * However, the database may hold several additional robust object points which have not been investigated/determined yet.
326  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
327  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
328  * @param randomGenerator Random generator object
329  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
330  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
331  * @param cameraMotion The camera motion (if known) for which stable object points will be extended/added, CM_UNKNOWN if the motion is not known
332  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
333  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
334  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
335  * @param finalCameraMotion Optional resulting motion of the camera
336  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
337  * @param progress Optional resulting progress with range [0, 1]
338  * @return True, if at least one 3D object point location and one camera pose are finally in the database
339  * @see extendStableObjectPoints(), determineInitialObjectPoints().
340  */
341  static bool extendStableObjectPoints(const PinholeCamera& pinholeCamera, Database& database, RandomGenerator& randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::CameraMotion cameraMotion = Solver3::CM_UNKNOWN, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, Solver3::CameraMotion* finalCameraMotion = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
342 
343  /**
344  * Removes all inaccurate locations of 3D object points from a given database.
345  * The topology will be left unchanged but the location is invalidated.<br>
346  * A location of a 3D object point is inaccurate if the projection error extends a specified threshold in at least one camera frame.<br>
347  * Whenever locations of 3D object points are removed from the database all camera poses will be updated as the pose value can slightly change due to the missing object points.<br>
348  * Therefore, several iterations of object-remove and pose-update steps can be applied so that the database stored only reliable and accurate object points and camera poses
349  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
350  * @param cameraMotion The motion of the camera, use CM_UNKNOWN if the motion is not known and may contain translation
351  * @param database The database providing the image point positions, the topology information and the locations of the 3D object points and valid camera pose values within the specified frame range
352  * @param randomGenerator Random generator object
353  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
354  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
355  * @param minimalCorrespondences The minimal number of point correspondences which must be visible in each frame so that a valid pose will be determined
356  * @param minimalValidCorrespondenceRatio The ratio of the minimal number of valid correspondences (the valid correspondences will be determined from a RANSAC iteration), with range [0, 1]
357  * @param maximalAverageSqrError The maximal averaged squared error between the projected 3D object points and their corresponding image point positions to count as valid
358  * @param maximalWorstSqrError The maximal worst squared error between the projected 3D object points and their corresponding image point positions to count as valid
359  * @param iterations The maximal number of object-remove and pose-update iterations; however, the function stop in anyway if no object point has been invalidated
360  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
361  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
362  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
363  * @return True, if at least one 3D object point location and one camera pose are finally in the database
364  */
365  static bool removeInaccurateObjectPoints(const PinholeCamera& pinholeCamera, const Solver3::CameraMotion cameraMotion, Database& database, RandomGenerator& randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, const unsigned int minimalCorrespondences, const Scalar minimalValidCorrespondenceRatio = Scalar(1), const Scalar maximalAverageSqrError = Scalar(3.5 * 3.5), const Scalar maximalWorstSqrError = Scalar(5.5 * 5.5), const unsigned int iterations = (unsigned int)(-1), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr);
366 
367  /**
368  * Optimizes a set of given 3D object point locations and all camera poses within a specified frame range iteratively.
369  * The optimization is not done by a bundle adjustment but by a separated optimization (first the optimization of object points with static camera poses, followed by an optimization of the camera poses with static object points).
370  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
371  * @param cameraMotion The motion of the camera, use CM_UNKNOWN if the motion is not known and may contain translation
372  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values, the database will received the optimized camera poses and object point locations
373  * @param randomGenerator Random generator object
374  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
375  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
376  * @param objectPointIds The ids of all object point having already a valid 3D location which will be optimized, object points which are not accurate enough will be removed from this set
377  * @param minimalCorrespondences The minimal number of point correspondences in a frame so that a valid pose will be determined
378  * @param beginWithPoseUpdate True, to start with one initial optimization of all camera poses before the object points will be optimized
379  * @param iterations The number of successive optimization iteration steps
380  * @param estimator The robust estimator which will be applied for pose determination
381  * @param minimalValidCorrespondenceRatio The ratio of the minimal number of valid correspondences (the valid correspondences will be determined from a RANSAC iteration), with range [0, 1]
382  * @param maximalRobustError The maximal robust error so that a determined pose counts as valid
383  * @param initialAverageError Optional resulting averaged initial error before the optimization has been invoked
384  * @param finalAverageError Optional resulting averaged final error after the optimization has finished
385  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
386  * @return True, if succeeded
387  */
388  static bool optimizeObjectPointsAndPosesIndividuallyIteratively(const PinholeCamera& pinholeCamera, const Solver3::CameraMotion cameraMotion, Database& database, RandomGenerator& randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, Indices32& objectPointIds, const unsigned int minimalCorrespondences, const bool beginWithPoseUpdate, const unsigned int iterations, const Geometry::Estimator::EstimatorType estimator, const Scalar minimalValidCorrespondenceRatio, const Scalar maximalRobustError, Scalar* initialAverageError, Scalar* finalAverageError, bool* abort);
389 
390  /**
391  * This functions extends an already reliable database with precise 3D object point locations and camera poses with new 3D object point locations visible in a specified region of interest in a specified camera frame.
392  * As the region of interest may cover any geometry structure this function tries to determine the locations of object points only that are visible in the specified frame for which the region of interest is defined.<br>
393  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
394  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
395  * @param randomGenerator Random generator object
396  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
397  * @param regionOfInterestFrame The index of the frame in which the region of interest is defined, with range [lowerFrame, upperFrame]
398  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
399  * @param regionOfInterest The region of interest defining a sub-region in a specific frame in which new object points will be investigated
400  * @param cameraMotion The camera motion (if known) for the given database
401  * @param minimalObservations The minimal number of observations a new object point must have (in arbitrary sibling camera pose)
402  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
403  * @return True, if at least one 3D object point location and one camera pose are finally in the database
404  * @see addObjectPointsInPlanarRegionOfInterest().
405  */
406  static bool addUnknownObjectPointsInRegionOfInterest(const PinholeCamera& pinholeCamera, Database& database, RandomGenerator& randomGenerator, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion& regionOfInterest, const Solver3::CameraMotion cameraMotion = Solver3::CM_UNKNOWN, const unsigned int minimalObservations = 10u, bool* abort = nullptr);
407 
408  /**
409  * This functions extends an already reliable database with precise 3D object point locations and camera poses with new 3D object point locations visible in a specified region of interest in a specified camera frame which covers a planar area (a plane).
410  * This function determines the plane which is covered by the region of interest and uses this plane to determine the locations of 3D object points which are not visible in the frame for which the region of interest is defined.<br>
411  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
412  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
413  * @param randomGenerator Random generator object
414  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
415  * @param regionOfInterestFrame The index of the frame in which the region of interest is defined, with range [lowerFrame, upperFrame]
416  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
417  * @param regionOfInterest The region of interest defining a sub-region in a specific frame in which new object points will be investigated
418  * @param cameraMotion The camera motion (if known) for the given database
419  * @param minimalObservations The minimal number of observations a new object point must have (in arbitrary sibling camera pose)
420  * @param plane Optional resulting plane that has been determined during the process
421  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
422  * @return True, if at least one 3D object point location and one camera pose are finally in the database
423  * @see addObjectPointsInRegionOfInterest().
424  */
425  static bool addUnknownObjectPointsInPlanarRegionOfInterest(const PinholeCamera& pinholeCamera, Database& database, RandomGenerator& randomGenerator, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion& regionOfInterest, const Solver3::CameraMotion cameraMotion = Solver3::CM_UNKNOWN, const unsigned int minimalObservations = 10u, Plane3* plane = nullptr, bool* abort = nullptr);
426 
427  /**
428  * Determines the number of valid correspondences (2D/3D correspondences which are used for pose determination) for image points which are visible in a planar region of interest for a defined range of frames.
429  * @param pinholeCamera The pinhole camera profile defining the projection, must be valid
430  * @param database The database providing the image point positions, the valid 3D object point locations, the valid camera poses and the topology information
431  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
432  * @param regionOfInterestFrame The index of the frame in which the region of interest is defined, with range [lowerFrame, upperFrame]
433  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
434  * @param regionOfInterest The region of interest defining a sub-region in a specific frame in which new object points will be investigated
435  * @param plane The plane of the region of interest, must be valid
436  * @param validCorrespondences Optional resulting number of valid correspondences for each frame in the defined frame range, the first number represents the lower frame
437  * @param meanCorrespondences Optional resulting mean number of valid correspondences
438  * @param medianCorrespondences Optional resulting median number of valid correspondences
439  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
440  * @return True, if succeeded
441  */
442  static bool determineValidCorrespondencesInPlanarRegionOfInterest(const PinholeCamera& pinholeCamera, const Database& database, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion& regionOfInterest, const Plane3& plane, Indices32* validCorrespondences = nullptr, Scalar* meanCorrespondences = nullptr, unsigned int* medianCorrespondences = nullptr, bool* abort = nullptr);
443 
444  /**
445  * Determines the number of visible image points in a planar region of interest for a defined range of frames.
446  * @param pinholeCamera The pinhole camera profile defining the projection, must be valid
447  * @param database The database providing the image point positions, the valid 3D object point locations, the valid camera poses and the topology information
448  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
449  * @param regionOfInterestFrame The index of the frame in which the region of interest is defined, with range [lowerFrame, upperFrame]
450  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
451  * @param regionOfInterest The region of interest defining a sub-region in a specific frame in which new object points will be investigated
452  * @param plane The plane of the region of interest, must be valid
453  * @param numberImagePoints Optional resulting number of visible image points for each frame in the defined frame range, the first number represents the lower frame
454  * @param meanNumberImagePoints Optional resulting mean number of visible image points
455  * @param medianNumberImagePoints Optional resulting median number of visible image points
456  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
457  * @return True, if succeeded
458  */
459  static bool determineNumberImagePointsInPlanarRegionOfInterest(const PinholeCamera& pinholeCamera, const Database& database, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion& regionOfInterest, const Plane3& plane, Indices32* numberImagePoints = nullptr, Scalar* meanNumberImagePoints = nullptr, unsigned int* medianNumberImagePoints = nullptr, bool* abort = nullptr);
460 
461  /**
462  * Adjusts camera poses specified for a specific camera profile without distortion parameters to a new camera profile without distortion parameters.
463  * @param oldCamera The old camera profile matching to the old camera poses, without distortion parameters
464  * @param oldPoses The old camera poses matching to the old camera profile
465  * @param newCamera The new camera profile for which the new camera poses will be determined, without distortion parameters
466  * @param newPoses The new camera poses matching to the provided new camera profile
467  * @param newObjectTransformations The new object transformations matching to the new camera poses, may contain scale and shear factors
468  * @return True, if succeeded
469  * @see adjustPosesAndPlaneToCamera().
470  */
471  static bool adjustPosesToCameraWithoutDistortion(const PinholeCamera& oldCamera, const TransformationMap& oldPoses, const PinholeCamera& newCamera, TransformationMap& newPoses, TransformationMap& newObjectTransformations);
472 
473  /**
474  * Adjusts camera poses specified for a specific camera profile (which may include distortion) to a new camera profile (which may include distortion).
475  * @param oldCamera The old camera profile matching to the old camera poses
476  * @param oldPoses The old camera poses matching to the old camera profile
477  * @param oldPlaneTransformation The transformation of the plane that has been determined together with the old camera poses
478  * @param selectionFrameIndex The index of the selection frame in which a region of interest has been defined to determine the track (the camera profile and camera poses)
479  * @param newCamera The new camera profile for which the new camera poses and plane transformation will be determined
480  * @param newPoses The new camera poses matching to the provided new camera profile
481  * @param newPlaneTransformation The transformation of the plane that matches to the new poses
482  * @param iterations The number of optimization iterations, with range [1, infinity), use 1 iteration for rotational camera motion to avoid skewed optimization results (as the scene is not based on stereo information)
483  * @param finalError Optional resulting final pixel error between projected 3D object points and their corresponding image points
484  * @return True, if succeeded
485  * @see adjustPosesToCameraWithoutDistortion().
486  */
487  static bool adjustPosesAndPlaneToCamera(const PinholeCamera& oldCamera, const OfflinePoses& oldPoses, const HomogenousMatrix4& oldPlaneTransformation, const unsigned int selectionFrameIndex, const PinholeCamera& newCamera, OfflinePoses& newPoses, HomogenousMatrix4& newPlaneTransformation, const unsigned int iterations = 30u, Scalar* finalError = nullptr);
488 
489  protected:
490 
491  /**
492  * Frame tracker run function.
493  * @param frameType Frame type of the tracking frames
494  * @return True, if the tracking succeeded
495  */
496  bool applyFrameTracking(const FrameType& frameType) override;
497 
498  /**
499  * The event function for the scheduler.
500  */
501  void onScheduler();
502 
503  /**
504  * This function extends a database providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
505  * The given database already provides valid camera poses for all frames within the defined frame range.
506  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
507  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
508  * @param cameraMotion The camera motion within the defined frame range
509  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
510  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
511  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
512  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
513  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
514  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
515  * @param progress Optional resulting progress with range [0, 1]
516  * @return True, if at least one 3D object point location and one camera pose are finally in the database
517  * @see extendStableObjectPoints().
518  */
519  static bool extendStableObjectPointsFull(const PinholeCamera& pinholeCamera, Database& database, const Solver3::CameraMotion cameraMotion, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
520 
521  /**
522  * This function extends a database providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
523  * The given database provides valid camera poses only for a subset of the frames within the defined frame range.
524  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
525  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
526  * @param cameraMotion The camera motion within the defined frame range
527  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
528  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
529  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
530  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
531  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
532  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
533  * @param progress Optional resulting progress with range [0, 1]
534  * @return True, if at least one 3D object point location and one camera pose are finally in the database
535  * @see extendStableObjectPoints().
536  */
537  static bool extendStableObjectPointsPartially(const PinholeCamera& pinholeCamera, Database& database, const Solver3::CameraMotion cameraMotion, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
538 
539  /**
540  * This function extends a database providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
541  * The camera has a rotational motion or is static within the defined frame range.<br>
542  * The given database already provides valid camera poses for all frames within the defined frame range.
543  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
544  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
545  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
546  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
547  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
548  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
549  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
550  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
551  * @param progress Optional resulting progress with range [0, 1]
552  * @return True, if at least one 3D object point location and one camera pose are finally in the database
553  * @see extendStableObjectPointsFull().
554  */
555  static bool extendStableObjectPointsFullRotational(const PinholeCamera& pinholeCamera, Database& database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
556 
557  /**
558  * This function extends a database providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
559  * The camera has a translational motion within the defined frame range.<br>
560  * The given database already provides valid camera poses for all frames within the defined frame range.
561  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
562  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
563  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
564  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
565  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
566  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
567  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
568  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
569  * @param progress Optional resulting progress with range [0, 1]
570  * @return True, if at least one 3D object point location and one camera pose are finally in the database
571  * @see extendStableObjectPointsFull(), stabilizeStableObjectPointsPartiallyTranslational(), extendStableObjectPointsPartiallyTranslational().
572  */
573  static bool extendStableObjectPointsFullTranslational(const PinholeCamera& pinholeCamera, Database& database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
574 
575  /**
576  * This function extends a database providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
577  * In detail, this function adds new object points mainly visible within the frame range with valid poses.<br>
578  * The camera has a rotational motion or is static within the defined frame range.<br>
579  * The given database provides valid camera poses only for a subset of the frames within the defined frame range.
580  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
581  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
582  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
583  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
584  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
585  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
586  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
587  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
588  * @param progress Optional resulting progress with range [0, 1]
589  * @return True, if at least one 3D object point location and one camera pose are finally in the database
590  * @see extendStableObjectPointsFull().
591  */
592  static bool extendStableObjectPointsPartiallyRotational(const PinholeCamera& pinholeCamera, Database& database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
593 
594  /**
595  * This function stabilizes a database already providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
596  * In detail, this function adds new object points mainly visible within the frame range with valid poses.<br>
597  * The camera has a translational motion within the defined frame range.<br>
598  * The given database provides valid camera poses only for a subset of the frames within the defined frame range.
599  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
600  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
601  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
602  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
603  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
604  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
605  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
606  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
607  * @param progress Optional resulting progress with range [0, 1]
608  * @return True, if at least one 3D object point location and one camera pose are finally in the database
609  * @see extendStableObjectPointsPartiallyTranslational().
610  */
611  static bool stabilizeStableObjectPointsPartiallyTranslational(const PinholeCamera& pinholeCamera, Database& database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
612 
613  /**
614  * This function extends a database providing stable/accurate and reliable locations of 3D object points visible within the defined frame range by additional reliable 3D object points.
615  * In detail, this function adds new object points to a database mainly visible at the 'borders' of the frame range with valid poses.<br>
616  * This function should be applied if a database holds valid poses for some (connected) frames within the entire range of frames.<br>
617  * The algorithm explicitly tries to extend the range of valid frame poses by adding object points visible at these border iteratively.<br>
618  * The camera has a translational motion within the defined frame range.<br>
619  * The given database provides valid camera poses only for a subset of the frames within the defined frame range.
620  * @param pinholeCamera The pinhole camera profile providing e.g., the dimension of the camera frame and the projection model
621  * @param database The database providing the image point positions, the topology information and some stable/reliable 3D object point locations and camera pose values
622  * @param lowerFrame The index of the lower frame border of the range of camera frames which will be investigated, with range [0, upperFrame]
623  * @param upperFrame The index of the upper frame border of the range of camera frames which will be investigated, with range [lowerFrame, infinity)
624  * @param correspondenceThreshold The threshold of point correspondences which must be visible in each camera frame so that a valid pose will be determined
625  * @param finalLowerValidPoseRange Optional resulting index of the lower frame within the resulting valid range of camera poses, with range [lowerFrame, upperFrame]
626  * @param finalUpperValidPoseRange Optional resulting index of the upper frame within the resulting valid range of camera poses, with range [lowerValidPose, upperFrame]
627  * @param abort Optional abort statement allowing to stop the execution; True, if the execution has to stop
628  * @param progress Optional resulting progress with range [0, 1]
629  * @return True, if at least one 3D object point location and one camera pose are finally in the database
630  * @see stabilizeStableObjectPointsPartiallyTranslational().
631  */
632  static bool extendStableObjectPointsPartiallyTranslational(const PinholeCamera& pinholeCamera, Database& database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold& correspondenceThreshold = Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int* finalLowerValidPoseRange = nullptr, unsigned int* finalUpperValidPoseRange = nullptr, bool* abort = nullptr, Scalar* progress = nullptr);
633 
634  /**
635  * Extracts a subset of object point ids and object points from a large set of object point ids, object points and their corresponding number of observations so that the subset contains object points with most observations.
636  * This functions sorts the number of observations so that the object points with most observations (hopefully the most stable object points) can be returned.
637  * @param objectPointIds The ids of all given object points
638  * @param objectPoints The locations of the object points, one location for each given id
639  * @param objectPointObservations The number of observations of all object points, one observation number for each given id
640  * @param subsetSize The number of resulting extracted object points, the actual resulting number of object points can be larger as several object points can have the same number of observations
641  * @param bestObjectPointIds The resulting ids of the subset of extracted object points
642  * @param bestObjectPoints The resulting locations of the subset of extracted object points
643  */
644  static void extractObjectPointsWithMostObservations(const Indices32& objectPointIds, const Vectors3& objectPoints, const Indices32& objectPointObservations, const size_t subsetSize, Indices32& bestObjectPointIds, Vectors3& bestObjectPoints);
645 
646  /**
647  * Sets an optional progress value to a fixed value.
648  * @param progress The optional progress value, nullptr if no progress value is provided
649  * @param value The fixed progress value to set, with range [0, 1]
650  */
651  static inline void setProgress(Scalar* progress, const Scalar value);
652 
653  /**
654  * Adjusts a transformation of a plane representing the geometry for a region of interest, with z-axis defining the normal of the plane.
655  * If the region is composed of two triangles defining a rectangle the x-axis of the transformation will be adjusted so that the projected axis fits to the most horizontal edge of the rectangle.<br>
656  * Otherwise, the x-axis of the transformation is adjusted so that the projected axis fits to the horizontal edge of the bounding box of the region of interest.<br>
657  * Further, the origin of the plane will be located at the center of the region of interest.
658  * @param pinholeCamera The pinhole camera profile defining e.g., the dimension of the camera frame and the projection model
659  * @param pose The camera pose of the frame in which the region of interest is defined
660  * @param regionOfInterest The region of interest to which the transformation will be adjusted to
661  * @param planeTransformation The transformation of the plane representing the geometry of the region of interest, with z-axis defining the normal of the plane
662  */
663  static bool adjustPlaneTransformationToRegionOfInterest(const PinholeCamera& pinholeCamera, const HomogenousMatrix4& pose, const CV::SubRegion& regionOfInterest, HomogenousMatrix4& planeTransformation);
664 
665  /**
666  * Sends environment information to the maintenance manager.
667  */
669 
670  protected:
671 
672  /// The database of this tracker.
674 
675  /// The tracking quality of this tracker.
676  TrackingQuality trackingQuality_ = TQ_AUTOMATIC;
677 
678  /// The horizontal field of view of the camera of this tracker in radian, with range (0, PI), -1 if the field of view is not known
679  Scalar cameraFieldOfView_ = Scalar(-1);
680 
681  /// The optimization strategy for the camera profile of this tracker.
683 
684  /// The abstract motion type of this tracker (the abstract motion type is a user-defined motion type which can be defined to force a specific kind of camera motion and is updated to the tracker determined camera motion).
685  AbstractMotionType abstractMotionType_ = AMT_UNKNOWN;
686 
687  /// The motion speed of this tracker (the visual information of the video frames respectively).
689 
690  /// The region of interest of this tracker, if any.
692 
693  /// The motion of the camera which has been detected by this tracker.
695 
696  // True, if the tracker uses only the region of interest and not the remaining frame information for tracking
697  bool soleRegionOfInterestApplication_ = false;
698 
699  /// The progress of this tracker for the current sub-task, with range [0, 1], -1 if undefined.
700  Scalar localProgress_ = Scalar(-1);
701 
702  /// The callback function that has been registered at the scheduler.
704 };
705 
706 inline SLAMTracker::ReliabilityPair::ReliabilityPair(const Scalar maximalCosine, const Scalar minimalObservationRatio) :
707  maximalCosineValue_(maximalCosine),
708  minimalObservationRatio_(minimalObservationRatio)
709 {
710  ocean_assert(maximalCosineValue_ > 0 && maximalCosineValue_ < 1);
711  ocean_assert(minimalObservationRatio_ > 0 && minimalObservationRatio_ <= 1);
712 }
713 
715 {
716  return maximalCosineValue_;
717 }
718 
720 {
721  return minimalObservationRatio_;
722 }
723 
724 template <unsigned int tLowerBoundary>
725 inline unsigned int SLAMTracker::ReliabilityPair::minimalObservations(const unsigned int overallObservation) const
726 {
727  return max(min(tLowerBoundary, overallObservation), (unsigned int)(Scalar(overallObservation) * minimalObservationRatio_));
728 }
729 
731 {
732  return regionOfInterest_;
733 }
734 
735 inline void SLAMTracker::setProgress(Scalar* progress, const Scalar value)
736 {
737  ocean_assert(value >= 0 && value <= 1);
738 
739  if (progress)
740  {
741  *progress = value;
742  }
743 }
744 
745 }
746 
747 }
748 
749 }
750 
751 #endif // META_OCEAN_TRACKING_OFFLINE_SLAM_TRACKER_H
This class implement a sub-region either defined by 2D triangles or defined by a binary mask.
Definition: SubRegion.h:32
Definition of a frame type composed by the frame dimension, pixel format and pixel origin.
Definition: Frame.h:30
EstimatorType
Definition of individual robust estimator types.
Definition: Estimator.h:34
@ ET_SQUARE
The standard square error estimator (L2).
Definition: Estimator.h:52
OptimizationStrategy
Definition of individual optimization strategies for camera parameters.
Definition: PinholeCamera.h:129
@ OS_INTRINSIC_PARAMETERS_DISTORTIONS
Optimization of all 8 intrinsic camera parameters including the distortion parameters: (2x focal leng...
Definition: PinholeCamera.h:143
This class implements a generator for random numbers.
Definition: RandomGenerator.h:42
This template class implements a smart object reference which is a specialization of an ObjectRef obj...
Definition: SmartObjectRef.h:90
This class implements a database for 3D object points, 2D image points and 6DOF camera poses.
Definition: Database.h:67
This class implements the base class for all visual offline tracker using frames to provide the track...
Definition: FrameTracker.h:46
TrackingQuality
Definition of individual tracking qualities.
Definition: OfflineTracker.h:54
AbstractMotionType
Definition of individual abstract camera motion types.
Definition: OfflineTracker.h:77
MotionSpeed
Definition of individual camera motion speeds.
Definition: PointPaths.h:43
@ MS_MODERATE
A moderate motion of the camera.
Definition: PointPaths.h:47
This class implements a pair of thresholds.
Definition: SLAMTracker.h:64
const Scalar minimalObservationRatio_
The minimal observation ratio.
Definition: SLAMTracker.h:101
Scalar maximalCosine() const
Returns the maximal cosine value.
Definition: SLAMTracker.h:714
const Scalar maximalCosineValue_
The maximal cosine value.
Definition: SLAMTracker.h:98
ReliabilityPair(const Scalar maximalCosine, const Scalar minimalObservationRatio)
Creates a new pair object.
Definition: SLAMTracker.h:706
unsigned int minimalObservations(const unsigned int overallObservation) const
Returns the minimal number of observations in relation to a given number of maximal possible observat...
Definition: SLAMTracker.h:725
Scalar minimalObservationRatio() const
Returns the minimal observation ratio.
Definition: SLAMTracker.h:719
This class implements a SLAM (Simultaneous Localization and Mapping) tracker for arbitrary environmen...
Definition: SLAMTracker.h:50
~SLAMTracker() override
Destructs a SLAM Tracker object.
static bool adjustPosesToCameraWithoutDistortion(const PinholeCamera &oldCamera, const TransformationMap &oldPoses, const PinholeCamera &newCamera, TransformationMap &newPoses, TransformationMap &newObjectTransformations)
Adjusts camera poses specified for a specific camera profile without distortion parameters to a new c...
static bool extendStableObjectPointsFullTranslational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
virtual AbstractMotionType abstractMotionType() const
Returns the abstract motion type of this tracker.
static bool extendStableObjectPointsPartiallyRotational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
const CV::SubRegion & regionOfInterest() const
Returns the specific region of interest which covers image content in the start frame of this tracker...
Definition: SLAMTracker.h:730
static void extractObjectPointsWithMostObservations(const Indices32 &objectPointIds, const Vectors3 &objectPoints, const Indices32 &objectPointObservations, const size_t subsetSize, Indices32 &bestObjectPointIds, Vectors3 &bestObjectPoints)
Extracts a subset of object point ids and object points from a large set of object point ids,...
static bool optimizeCamera(const PinholeCamera &pinholeCamera, const Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const bool findInitialFieldOfView, const PinholeCamera::OptimizationStrategy optimizationStrategy, const unsigned int maximalKeyFrames, PinholeCamera &optimizedCamera, Database &optimizedDatabase, Solver3::CameraMotion *cameraMotion=nullptr, bool *abort=nullptr, Scalar *finalMeanSqrError=nullptr)
Optimizes the camera profile for a database with stable initial object points.
virtual TrackingQuality trackingQuality() const
Returns the tracking quality of this tracker.
static bool determineNumberImagePointsInPlanarRegionOfInterest(const PinholeCamera &pinholeCamera, const Database &database, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion &regionOfInterest, const Plane3 &plane, Indices32 *numberImagePoints=nullptr, Scalar *meanNumberImagePoints=nullptr, unsigned int *medianNumberImagePoints=nullptr, bool *abort=nullptr)
Determines the number of visible image points in a planar region of interest for a defined range of f...
virtual bool setCameraOptimizationStrategy(const PinholeCamera::OptimizationStrategy optimizationStrategy)
Sets the optimization strategy for the camera profile of this tracker.
CV::SubRegion regionOfInterest_
The region of interest of this tracker, if any.
Definition: SLAMTracker.h:691
Database database_
The database of this tracker.
Definition: SLAMTracker.h:673
void maintenanceSendEnvironment()
Sends environment information to the maintenance manager.
static bool extendInitialObjectPoints(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr)
Determines the locations of further (stable and reliable) 3D object points which are visible within a...
bool extractPoses(const unsigned int lowerFrameIndex, const unsigned int upperFrameIndex, OfflinePoses &offlinePoses, const unsigned int minimalCorrespondences=5u, const Geometry::Estimator::EstimatorType estimator=Geometry::Estimator::ET_SQUARE, const Scalar minimalValidCorrespondenceRatio=Scalar(1), const Scalar ransacMaximalSqrError=Scalar(3.5 *3.5), const Scalar maximalRobustError=Scalar(3.5 *3.5), Scalar *finalAverageError=nullptr, Worker *worker=nullptr, bool *abort=nullptr) const
Extracts the poses from this tracker for a specified frame range not considering any specific region ...
virtual bool setAbstractMotionType(const AbstractMotionType abstractMotionType)
Sets the abstract motion type of this tracker, if known before that tracker starts.
static bool extendStableObjectPoints(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::CameraMotion cameraMotion=Solver3::CM_UNKNOWN, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, Solver3::CameraMotion *finalCameraMotion=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static void setProgress(Scalar *progress, const Scalar value)
Sets an optional progress value to a fixed value.
Definition: SLAMTracker.h:735
virtual bool setTrackingQuality(const TrackingQuality trackingQuality)
Sets the tracking quality of the tracker.
SLAMTracker()=default
Creates a new SLAM Tracker object.
virtual PointPaths::MotionSpeed motionSpeed() const
Returns the motion speed of this tracker (the speed of the visual information in the frames on which ...
virtual Scalar cameraFieldOfView() const
Returns the used-defined horizontal field of view of the camera.
static bool extendStableObjectPointsFullRotational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static bool extendStableObjectPointsPartiallyTranslational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
bool start() override
Starts the offline tracker.
static bool removeInaccurateObjectPoints(const PinholeCamera &pinholeCamera, const Solver3::CameraMotion cameraMotion, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, const unsigned int minimalCorrespondences, const Scalar minimalValidCorrespondenceRatio=Scalar(1), const Scalar maximalAverageSqrError=Scalar(3.5 *3.5), const Scalar maximalWorstSqrError=Scalar(5.5 *5.5), const unsigned int iterations=(unsigned int)(-1), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr)
Removes all inaccurate locations of 3D object points from a given database.
static bool extendStableObjectPointsPartially(const PinholeCamera &pinholeCamera, Database &database, const Solver3::CameraMotion cameraMotion, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static bool determineInitialObjectPoints(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int *startFrame, const unsigned int upperFrame, const CV::SubRegion &regionOfInterest, const bool soleRegionOfInterest, unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
Determines the location of some initial 3D object points which are all visible within a defined frame...
bool setRegionOfInterest(const CV::SubRegion &regionOfInterest, const bool soleApplication)
Sets a specific region of interest which covers image content in the start frame of this tracker.
static bool determineValidCorrespondencesInPlanarRegionOfInterest(const PinholeCamera &pinholeCamera, const Database &database, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion &regionOfInterest, const Plane3 &plane, Indices32 *validCorrespondences=nullptr, Scalar *meanCorrespondences=nullptr, unsigned int *medianCorrespondences=nullptr, bool *abort=nullptr)
Determines the number of valid correspondences (2D/3D correspondences which are used for pose determi...
std::map< unsigned int, HomogenousMatrix4 > TransformationMap
Definition of a map mapping frame indices to transformations e.g., camera poses or object transformat...
Definition: SLAMTracker.h:56
Scheduler::Callback schedulerCallback_
The callback function that has been registered at the scheduler.
Definition: SLAMTracker.h:703
static bool extendStableObjectPointsFull(const PinholeCamera &pinholeCamera, Database &database, const Solver3::CameraMotion cameraMotion, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function extends a database providing stable/accurate and reliable locations of 3D object points...
static bool adjustPlaneTransformationToRegionOfInterest(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const CV::SubRegion &regionOfInterest, HomogenousMatrix4 &planeTransformation)
Adjusts a transformation of a plane representing the geometry for a region of interest,...
virtual bool setCameraFieldOfView(const Scalar fovX)
Explicitly sets the horizontal field of view of the camera.
static bool adjustPosesAndPlaneToCamera(const PinholeCamera &oldCamera, const OfflinePoses &oldPoses, const HomogenousMatrix4 &oldPlaneTransformation, const unsigned int selectionFrameIndex, const PinholeCamera &newCamera, OfflinePoses &newPoses, HomogenousMatrix4 &newPlaneTransformation, const unsigned int iterations=30u, Scalar *finalError=nullptr)
Adjusts camera poses specified for a specific camera profile (which may include distortion) to a new ...
bool extractPoses(const unsigned int lowerFrameIndex, const unsigned int regionOfInterestFrameIndex, const unsigned int upperFrameIndex, const CV::SubRegion &regionOfInterest, OfflinePoses &offlinePoses, HomogenousMatrix4 &planeTransformation, const unsigned int minimalCorrespondences=5u, const unsigned int minimalKeyFrames=50u, const Geometry::Estimator::EstimatorType estimator=Geometry::Estimator::ET_SQUARE, const Scalar minimalValidCorrespondenceRatio=Scalar(1), const Scalar ransacMaximalSqrError=Scalar(3.5 *3.5), const Scalar maximalRobustError=Scalar(3.5 *3.5), Scalar *finalAverageError=nullptr, Worker *worker=nullptr, bool *abort=nullptr) const
Extracts the poses from this tracker for a specific region of interest.
static bool stabilizeStableObjectPointsPartiallyTranslational(const PinholeCamera &pinholeCamera, Database &database, const unsigned int lowerFrame, const unsigned int upperFrame, const Solver3::RelativeThreshold &correspondenceThreshold=Solver3::RelativeThreshold(10u, Scalar(0.5), 25u), unsigned int *finalLowerValidPoseRange=nullptr, unsigned int *finalUpperValidPoseRange=nullptr, bool *abort=nullptr, Scalar *progress=nullptr)
This function stabilizes a database already providing stable/accurate and reliable locations of 3D ob...
static bool optimizeObjectPointsAndPosesIndividuallyIteratively(const PinholeCamera &pinholeCamera, const Solver3::CameraMotion cameraMotion, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int upperFrame, Indices32 &objectPointIds, const unsigned int minimalCorrespondences, const bool beginWithPoseUpdate, const unsigned int iterations, const Geometry::Estimator::EstimatorType estimator, const Scalar minimalValidCorrespondenceRatio, const Scalar maximalRobustError, Scalar *initialAverageError, Scalar *finalAverageError, bool *abort)
Optimizes a set of given 3D object point locations and all camera poses within a specified frame rang...
virtual bool setMotionSpeed(const PointPaths::MotionSpeed motionSpeed)
Sets the motion speed of this tracker.
void onScheduler()
The event function for the scheduler.
virtual PinholeCamera::OptimizationStrategy cameraOptimizationStrategy() const
Returns the camera profile optimization strategy of this tracker.
static bool addUnknownObjectPointsInPlanarRegionOfInterest(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion &regionOfInterest, const Solver3::CameraMotion cameraMotion=Solver3::CM_UNKNOWN, const unsigned int minimalObservations=10u, Plane3 *plane=nullptr, bool *abort=nullptr)
This functions extends an already reliable database with precise 3D object point locations and camera...
bool stop(const unsigned int timeout=0u) override
Stops the offline tracker.
bool applyFrameTracking(const FrameType &frameType) override
Frame tracker run function.
static bool addUnknownObjectPointsInRegionOfInterest(const PinholeCamera &pinholeCamera, Database &database, RandomGenerator &randomGenerator, const unsigned int lowerFrame, const unsigned int regionOfInterestFrame, const unsigned int upperFrame, const CV::SubRegion &regionOfInterest, const Solver3::CameraMotion cameraMotion=Solver3::CM_UNKNOWN, const unsigned int minimalObservations=10u, bool *abort=nullptr)
This functions extends an already reliable database with precise 3D object point locations and camera...
Definition of a class allowing to define a relative threshold with lower and upper boundary for indiv...
Definition: Solver3.h:93
CameraMotion
Definition of individual camera motion types.
Definition: Solver3.h:49
@ CM_INVALID
Invalid camera motion.
Definition: Solver3.h:51
@ CM_UNKNOWN
An unknown (arbitrary) camera motion with rotational and translational motion.
Definition: Solver3.h:71
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
std::vector< Vector3 > Vectors3
Definition of a vector holding Vector3 objects.
Definition: Vector3.h:65
SmartObjectRef< SLAMTracker, OfflineTracker > SLAMTrackerRef
Definition of an object reference holding a PlanarRectangleTracker object.
Definition: SLAMTracker.h:33
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15