Ocean
Loading...
Searching...
No Matches
tracking/VisualTracker.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_VISUAL_TRACKER_H
9#define META_OCEAN_TRACKING_VISUAL_TRACKER_H
10
14
15#include "ocean/base/Frame.h"
16#include "ocean/base/Worker.h"
17
21
22#include <vector>
23
24namespace Ocean
25{
26
27namespace Tracking
28{
29
30// Forward declaration.
31class VisualTracker;
32
33/**
34 * Definition of an object reference covering a visual tracker object.
35 * @see VisualTracker.
36 * @ingroup tracking
37 */
39
40/**
41 * This class implements a base class for all visual tracker objects.
42 * @ingroup tracking
43 */
44class OCEAN_TRACKING_EXPORT VisualTracker : public Tracker
45{
46 public:
47
48 /**
49 * Definition of an object id.
50 */
51 typedef unsigned int ObjectId;
52
53 /**
54 * Definition of a simple tracking sample combining a tracking object id with a transformation.
55 */
57 {
58 public:
59
60 /**
61 * Creates a new sample object with in valid parameters.
62 */
64
65 /**
66 * Creates a new sample object.
67 * @param transformation The transformation of the new sample
68 * @param id The object id of the new sample
69 */
70 inline TransformationSample(const HomogenousMatrix4& transformation, const ObjectId id);
71
72 public:
73
74 /**
75 * Returns the transformation of this sample.
76 * @return Sample transformation
77 */
78 inline const HomogenousMatrix4& transformation() const;
79
80 /**
81 * Returns the id of this sample.
82 * @return Sample id
83 */
84 inline unsigned int id() const;
85
86 protected:
87
88 /// The sample's transformation.
89 HomogenousMatrix4 transformation_ = HomogenousMatrix4(false);
90
91 /// The sample's object id.
92 ObjectId id_ = ObjectId(-1);
93 };
94
95 /**
96 * Definition of a vector holding a transformation sample object.
97 */
98 typedef std::vector<TransformationSample> TransformationSamples;
99
100 public:
101
102 /**
103 * Returns the maximal expected pose position offset between two successive frames for this tracker.
104 * @return Maximal pose position offset separately for each axis
105 */
106 inline const Vector3& maximalPositionOffset() const;
107
108 /**
109 * Returns the maximal expected pose orientation offset between two successive frames for this tracker.
110 * @return Maximal pose orientation offset in radian
111 */
112 inline Scalar maximalOrientationOffset() const;
113
114 /**
115 * Sets or changes the maximal expected pose position offset between two successive frames for this tracker.
116 * @param positionOffset New position offset to be set for each axis separately, with range (0, infinity)
117 * @return True, if succeeded
118 */
119 virtual bool setMaxPositionOffset(const Vector3& positionOffset);
120
121 /**
122 * Sets or changes the maximal expected pose orientation offset between two successive frames for this tracker.
123 * @param orientationOffset New orientation offset to be set in radian, with range (0, PI)
124 * @return True, if succeeded
125 */
126 virtual bool setMaxOrientationOffset(const Scalar orientationOffset);
127
128 /**
129 * Executes the tracking step for a collection of frames and corresponding cameras
130 * This function allows to specify an absolute orientation 'absoluteOrientation' provided by e.g., an IMU sensor.<br>
131 * This orientation can be defined in relation to an independent coordinate system not related with the tracking objects (as long as this coordinate system does not change between successive calls).<br>
132 * The tracker can use the provided orientation to improve tracking robustness.
133 * @note The base implementation will only accept a single frame and camera and will return false for multiple frames and cameras. If the camera type is not a pinhole camera, the input frame will be undistorted and the camera will be converted to a pinhole camera, which is an expensive operation. For customization this function needs to be overriden.
134 * @note Once the deprecated function below has been removed, this function will become purely virtual. For any derived class, it is strongly suggested to provide an override of this function.
135 * @param frames The frames to be used for tracking, must have at least one element and have same number of elements as `anyCameras`, all elements must be valid
136 * @param anyCameras The camera objects associated with the frames, with width and height must match that of each corresponding frame, must have same number of elements as `frames`, all elements must be valid
137 * @param transformations The resulting 6DOF poses combined with the tracking IDs
138 * @param world_R_camera An optional absolute orientation of the camera in the moment the frame was taken, defined in a coordinate system (e.g., world) not related with the tracking objects, an invalid object otherwise
139 * @param worker An optional worker object
140 * @return True, if succeeded
141 */
142 virtual bool determinePoses(const Frames& frames, const SharedAnyCameras& anyCameras, TransformationSamples& transformations, const Quaternion& world_R_camera = Quaternion(false), Worker* worker = nullptr);
143
144 /**
145 * Deprecated.
146 *
147 * Executes the tracking for a given frame.
148 * This function allows to specify an absolute orientation 'absoluteOrientation' provided by e.g., an IMU sensor.<br>
149 * This orientation can be defined in relation to an independent coordinate system not related with the tracking objects (as long as this coordinate system does not change between successive calls).<br>
150 * The tracker can use the provided orientation to improve tracking robustness.
151 * @param frame The frame to be used for tracking, must be valid
152 * @param pinholeCamera The pinhole camera object associated with the frame, with width and height matching with the frame's resolution
153 * @param frameIsUndistorted True, if the original input frame is undistorted and thus feature must not be undistorted explicitly
154 * @param transformations Resulting 6DOF poses combined with the tracking ids
155 * @param world_R_camera Optional absolute orientation of the camera in the moment the frame was taken, defined in a coordinate system (e.g., world) not related with the tracking objects, an invalid object otherwise
156 * @param worker Optional worker object
157 * @return True, if succeeded
158 */
159 virtual bool determinePoses(const Frame& frame, const PinholeCamera& pinholeCamera, const bool frameIsUndistorted, TransformationSamples& transformations, const Quaternion& world_R_camera = Quaternion(false), Worker* worker = nullptr) = 0;
160
161 protected:
162
163 /**
164 * Creates a new visual tracker object.
165 */
166 VisualTracker() = default;
167
168 protected:
169
170 /// Pose motion model to predict the pose of the next frame.
172
173 /// Maximal pose position offset between two frames.
174 Vector3 maxPositionOffset_ = Vector3(Scalar(0.08), Scalar(0.08), Scalar(0.08));
175
176 /// Maximal pose orientation offset between two frames, in radian angle.
177 Scalar maxOrientationOffset_ = Numeric::deg2rad(15);
178
179 /// Tracker lock object.
180 mutable Lock lock_;
181};
182
184 transformation_(transformation),
185 id_(id)
186{
187 // nothing to do here
188}
189
191{
192 return transformation_;
193}
194
199
201{
202 return maxPositionOffset_;
203}
204
209
210}
211
212}
213
214#endif // META_OCEAN_TRACKING_VISUAL_TRACKER_H
This class implements Ocean's image class.
Definition Frame.h:1808
This class implements a recursive lock object.
Definition Lock.h:31
This template class implements a object reference with an internal reference counter.
Definition base/ObjectRef.h:58
This class implements a 6DOF pose with internal motion model.
Definition MotionModel.h:30
This class implements the base class for all tracker object.
Definition tracking/Tracker.h:24
Definition of a simple tracking sample combining a tracking object id with a transformation.
Definition tracking/VisualTracker.h:57
TransformationSample()=default
Creates a new sample object with in valid parameters.
const HomogenousMatrix4 & transformation() const
Returns the transformation of this sample.
Definition tracking/VisualTracker.h:190
unsigned int id() const
Returns the id of this sample.
Definition tracking/VisualTracker.h:195
This class implements a base class for all visual tracker objects.
Definition tracking/VisualTracker.h:45
virtual bool determinePoses(const Frames &frames, const SharedAnyCameras &anyCameras, TransformationSamples &transformations, const Quaternion &world_R_camera=Quaternion(false), Worker *worker=nullptr)
Executes the tracking step for a collection of frames and corresponding cameras This function allows ...
virtual bool setMaxOrientationOffset(const Scalar orientationOffset)
Sets or changes the maximal expected pose orientation offset between two successive frames for this t...
Vector3 maxPositionOffset_
Maximal pose position offset between two frames.
Definition tracking/VisualTracker.h:174
MotionModel motionModel_
Pose motion model to predict the pose of the next frame.
Definition tracking/VisualTracker.h:171
VisualTracker()=default
Creates a new visual tracker object.
Lock lock_
Tracker lock object.
Definition tracking/VisualTracker.h:180
virtual bool setMaxPositionOffset(const Vector3 &positionOffset)
Sets or changes the maximal expected pose position offset between two successive frames for this trac...
unsigned int ObjectId
Definition of an object id.
Definition tracking/VisualTracker.h:51
virtual bool determinePoses(const Frame &frame, const PinholeCamera &pinholeCamera, const bool frameIsUndistorted, TransformationSamples &transformations, const Quaternion &world_R_camera=Quaternion(false), Worker *worker=nullptr)=0
Deprecated.
std::vector< TransformationSample > TransformationSamples
Definition of a vector holding a transformation sample object.
Definition tracking/VisualTracker.h:98
const Vector3 & maximalPositionOffset() const
Returns the maximal expected pose position offset between two successive frames for this tracker.
Definition tracking/VisualTracker.h:200
Scalar maxOrientationOffset_
Maximal pose orientation offset between two frames, in radian angle.
Definition tracking/VisualTracker.h:177
Scalar maximalOrientationOffset() const
Returns the maximal expected pose orientation offset between two successive frames for this tracker.
Definition tracking/VisualTracker.h:205
This class implements a worker able to distribute function calls over different threads.
Definition Worker.h:33
std::vector< Frame > Frames
Definition of a vector holding padding frames.
Definition Frame.h:1771
float Scalar
Definition of a scalar type.
Definition Math.h:129
SharedAnyCamerasT< Scalar > SharedAnyCameras
Definition of a vector holding AnyCamera objects.
Definition AnyCamera.h:90
ObjectRef< VisualTracker > VisualTrackerRef
Definition of an object reference covering a visual tracker object.
Definition tracking/VisualTracker.h:38
The namespace covering the entire Ocean framework.
Definition Accessor.h:15