Ocean
Loading...
Searching...
No Matches
FeatureTracker6DOF.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_ORB_FEATURE_TRACKER_6DOF_H
9#define META_OCEAN_TRACKING_ORB_FEATURE_TRACKER_6DOF_H
10
13
14#include "ocean/base/Frame.h"
15#include "ocean/base/Lock.h"
18#include "ocean/base/Worker.h"
19
22
24
25namespace Ocean
26{
27
28namespace Tracking
29{
30
31namespace ORB
32{
33
34/**
35 * This class implements a 6DOF ORB feature tracker.
36 * @ingroup trackingorb
37 */
38class OCEAN_TRACKING_ORB_EXPORT FeatureTracker6DOF : virtual public VisualTracker
39{
40 public:
41
42 /**
43 * Creates a new feature tracker object.
44 */
45 explicit FeatureTracker6DOF() = default;
46
47 /**
48 * Destructs a feature tracker object.
49 */
51
52 /**
53 * Sets or changes the feature map for this tracker.
54 * @param featureMap ORB feature map to set, must be created with the same feature detector as the tracker
55 * @param autoUpdateMaxPositionOffset State determining whether the maximal position offset between two frames will be adjusted to the feature map size automatically
56 * @return True, if succeeded
57 */
58 bool setFeatureMap(const FeatureMap& featureMap, const bool autoUpdateMaxPositionOffset = true);
59
60 /**
61 * Executes the 6DOF tracking for a given frame.
62 * @see VisualTracker::determinePoses().
63 */
64 bool determinePoses(const Frame& frame, const PinholeCamera& pinholeCamera, const bool frameIsUndistorted, TransformationSamples& transformations, const Quaternion& previousCamera_R_camera = Quaternion(false), Worker* worker = nullptr) override;
65
66 protected:
67
68 /**
69 * Determines the 6DOF tracking for a given frame and given integral image.
70 * @param frame The frame to be used for tracking
71 * @param integralImage Integral image of the tracking frame
72 * @param pinholeCamera The pinhole camera object associated with the frame
73 * @param frameIsUndistorted True, if the original input frame is undistorted and thus feature must not be undistorted explicitly
74 * @param pose Resulting 6DOF pose
75 * @param worker Optional worker object
76 * @return True, if succeeded
77 */
78 bool determinePose(const Frame& frame, const uint32_t* integralImage, const PinholeCamera& pinholeCamera, const bool frameIsUndistorted, HomogenousMatrix4& pose, Worker* worker = nullptr);
79
80 /**
81 * Determines the pose if no previous information is given.
82 * @param features Already detected features to be used for pose determination
83 * @param frame The frame to be used for tracking
84 * @param pinholeCamera The pinhole camera object associated with the frame
85 * @param pose Resulting 6DOF pose
86 * @param worker Optional worker object
87 * @return True, if succeeded
88 */
89 bool determinePoseWithoutKnowledge(CV::Detector::ORBFeatures& features, const Frame& frame, const PinholeCamera& pinholeCamera, HomogenousMatrix4& pose, Worker* worker);
90
91 /**
92 * Determines the pose if the pose from the previous frame is given.
93 * @param features Already detected ORB features in the given frame
94 * @param frame The frame to be used fro tracking
95 * @param pinholeCamera The pinhole camera object associated with the frame
96 * @param pose Resulting 6DOF pose
97 * @return True, if succeeded
98 */
99 bool determinePoseWithPreviousPose(CV::Detector::ORBFeatures& features, const Frame& frame, const PinholeCamera& pinholeCamera, HomogenousMatrix4& pose);
100
101 /**
102 * Creates the lined integral image of the given frame.
103 * @param frame The frame for which the lined integral image will be created, must be valid
104 * @param worker Optional worker object
105 * @return Pointer to the integral image data
106 */
107 const uint32_t* createLinedIntegralImage(const Frame& frame, Worker* worker);
108
109 protected:
110
111 /// Feature map holding all reference features.
113
114 /// Timestamp of the most recent pose.
116
117 /// Most recent pose (object_T_camera).
119
120 /// Random generator object.
122
123 /// Feature strength threshold currently used for feature detection.
124 unsigned int featureStrengthThreshold_ = 35u;
125
126 // The percentage (in relation to the number of descriptor bits) of the maximal hamming distance so that two descriptors count as similar, with range [0, 1]
127 float matchingThreshold_ = 0.2f;
128
129 /// Number of detected features in the current frame.
130 size_t numberDetectedFeatures_ = 0u;
131
132 /// True, if projected 3D features are used for determine pose.
133 bool useProjectedFeatures_ = false;
134
135 // True, to use Harris corners; False, to use FAST features.
136 bool usingHarrisFeatures_ = false;
137
138 private:
139
140 /// Internal grayscale frame with format FORMAT_Y8.
142
143 /// Internal lined integral image for the most recent frame.
145};
146
147}
148
149}
150
151}
152
153#endif // META_OCEAN_TRACKING_ORB_FEATURE_TRACKER_6DOF_H
This class implements Ocean's image class.
Definition Frame.h:1808
This class implements a generator for random numbers.
Definition RandomGenerator.h:42
This class implements a timestamp.
Definition Timestamp.h:36
This class implements a feature map for ORB features.
Definition FeatureMap.h:39
This class implements a 6DOF ORB feature tracker.
Definition FeatureTracker6DOF.h:39
Timestamp recentTimestamp_
Timestamp of the most recent pose.
Definition FeatureTracker6DOF.h:115
const uint32_t * createLinedIntegralImage(const Frame &frame, Worker *worker)
Creates the lined integral image of the given frame.
FeatureTracker6DOF()=default
Creates a new feature tracker object.
Frame linedIntegralImage_
Internal lined integral image for the most recent frame.
Definition FeatureTracker6DOF.h:144
bool determinePoseWithPreviousPose(CV::Detector::ORBFeatures &features, const Frame &frame, const PinholeCamera &pinholeCamera, HomogenousMatrix4 &pose)
Determines the pose if the pose from the previous frame is given.
Frame yFrame_
Internal grayscale frame with format FORMAT_Y8.
Definition FeatureTracker6DOF.h:141
~FeatureTracker6DOF() override
Destructs a feature tracker object.
RandomGenerator randomGenerator_
Random generator object.
Definition FeatureTracker6DOF.h:121
bool determinePoseWithoutKnowledge(CV::Detector::ORBFeatures &features, const Frame &frame, const PinholeCamera &pinholeCamera, HomogenousMatrix4 &pose, Worker *worker)
Determines the pose if no previous information is given.
bool setFeatureMap(const FeatureMap &featureMap, const bool autoUpdateMaxPositionOffset=true)
Sets or changes the feature map for this tracker.
bool determinePose(const Frame &frame, const uint32_t *integralImage, const PinholeCamera &pinholeCamera, const bool frameIsUndistorted, HomogenousMatrix4 &pose, Worker *worker=nullptr)
Determines the 6DOF tracking for a given frame and given integral image.
bool determinePoses(const Frame &frame, const PinholeCamera &pinholeCamera, const bool frameIsUndistorted, TransformationSamples &transformations, const Quaternion &previousCamera_R_camera=Quaternion(false), Worker *worker=nullptr) override
Executes the 6DOF tracking for a given frame.
FeatureMap featureMap_
Feature map holding all reference features.
Definition FeatureTracker6DOF.h:112
This class implements a base class for all visual tracker objects.
Definition tracking/VisualTracker.h:45
std::vector< TransformationSample > TransformationSamples
Definition of a vector holding a transformation sample object.
Definition tracking/VisualTracker.h:98
This class implements a worker able to distribute function calls over different threads.
Definition Worker.h:33
std::vector< ORBFeature > ORBFeatures
Definition of a vector holding ORB features.
Definition ORBFeature.h:32
The namespace covering the entire Ocean framework.
Definition Accessor.h:15