![]() |
NDEVR
API Documentation
|
Main tracking thread that processes each frame and estimates camera pose. More...
Public Types | |
| enum | eTrackingState { SYSTEM_NOT_READY = -1 , NO_IMAGES_YET = 0 , NOT_INITIALIZED = 1 , OK = 2 , RECENTLY_LOST = 3 , LOST = 4 , OK_KLT = 5 } |
| Tracking state enumeration. More... | |
| enum | GlobalFrameAlignmentState { NO_MEAS_YET , FIRST_GLOBAL_MEAS_SET , ALIGNING , ALIGNED } |
| State of global frame alignment (GPS/global position). More... | |
Public Member Functions | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | Tracking (OrbSLAM *pSys, ORBVocabulary *pVoc, Atlas *pAtlas, KeyFrameDatabase *pKFDB, const SLAMParameters ¶ms, LogPtr log) |
| Constructs the tracker. | |
| ~Tracking () | |
| Destructor. | |
| void | appendGPSData (const Buffer< GlobalPosition * > gps_measurements, fltp08 time_offset) |
| Appends GPS measurements to the processing queue. | |
| void | appendImuData (Buffer< IMU::Point > imu_measurements, fltp08 time_offset) |
| Appends IMU measurements to the processing queue. | |
| void | CreateMapInAtlas () |
| Creates a new map in the Atlas. | |
| bool | ensureValidData (const cv::Mat &imRectLeft) const |
| Validates that the input image data is usable. | |
| KeyFrame * | GetLastKeyFrame () |
| Returns the last keyframe. | |
| int | GetMatchesInliers () |
| Returns the number of inlier matches in the current frame. | |
| Sophus::SE3f | GrabImageMonocular (OrbTrackingInfo &info) |
| Processes a monocular image and returns the estimated pose. | |
| Sophus::SE3f | GrabImageRGBD (OrbTrackingInfo &info) |
| Processes an RGB-D frame and returns the estimated pose. | |
| Sophus::SE3f | GrabImageStereo (OrbTrackingInfo &info) |
| Processes a stereo image pair and returns the estimated pose. | |
| void | InformOnlyTracking (bool flag) |
| Enables or disables localization-only tracking. | |
| bool | parseCamParamFile (const SLAMParameters ¶ms) |
| Parses camera parameters from SLAM configuration. | |
| bool | parseIMUParamFile (const SLAMParameters ¶ms) |
| Parses IMU parameters from SLAM configuration. | |
| bool | parseORBParamFile (const SLAMParameters ¶ms) |
| Parses ORB extractor parameters from SLAM configuration. | |
| const Sensor & | sensor () const |
| Returns the sensor configuration. | |
| void | SetLocalMapper (LocalMapping *pLocalMapper) |
| Sets the local mapper reference. | |
| void | SetLoopClosing (LoopClosing *pLoopClosing) |
| Sets the loop closer reference. | |
| void | setParams (const SLAMParameters ¶ms) |
| Updates SLAM parameters. | |
| void | setState (eTrackingState state) |
| Sets the tracking state. | |
| eTrackingState | state () const |
| Returns the current tracking state. | |
| void | UpdateFrameIMU (fltp04 scale, const IMU::Bias &b, KeyFrame *pCurrentKeyFrame) |
| Updates frame IMU data after scale/bias refinement. | |
Main tracking thread that processes each frame and estimates camera pose.
Receives frames from the main thread, extracts features, performs tracking (via motion model, reference keyframe, or relocalization), decides when to insert new keyframes, and interfaces with local mapping and loop closing.
Definition at line 32 of file Tracking.h.
Tracking state enumeration.
| Enumerator | |
|---|---|
| SYSTEM_NOT_READY | System not yet ready. |
| NO_IMAGES_YET | No images have been received. |
| NOT_INITIALIZED | Map not yet initialized. |
| OK | Tracking is successful. |
| RECENTLY_LOST | Recently lost tracking. |
| LOST | Tracking is lost. |
| OK_KLT | Tracking via KLT optical flow. |
Definition at line 36 of file Tracking.h.
State of global frame alignment (GPS/global position).
| Enumerator | |
|---|---|
| NO_MEAS_YET | No global measurements received. |
| FIRST_GLOBAL_MEAS_SET | First global measurement has been set. |
| ALIGNING | Alignment in progress. |
| ALIGNED | Global alignment complete. |
Definition at line 47 of file Tracking.h.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW Tracking::Tracking | ( | OrbSLAM * | pSys, |
| ORBVocabulary * | pVoc, | ||
| Atlas * | pAtlas, | ||
| KeyFrameDatabase * | pKFDB, | ||
| const SLAMParameters & | params, | ||
| LogPtr | log ) |
| bool Tracking::ensureValidData | ( | const cv::Mat & | imRectLeft | ) | const |
Validates that the input image data is usable.
| [in] | imRectLeft | The left/main rectified image. |
|
inline |
Returns the last keyframe.
Definition at line 145 of file Tracking.h.
|
inline |
Returns the number of inlier matches in the current frame.
Definition at line 155 of file Tracking.h.
| Sophus::SE3f Tracking::GrabImageMonocular | ( | OrbTrackingInfo & | info | ) |
Processes a monocular image and returns the estimated pose.
| [in] | info | Tracking info with the monocular image. |
| Sophus::SE3f Tracking::GrabImageRGBD | ( | OrbTrackingInfo & | info | ) |
Processes an RGB-D frame and returns the estimated pose.
| [in] | info | Tracking info with color and depth images. |
| Sophus::SE3f Tracking::GrabImageStereo | ( | OrbTrackingInfo & | info | ) |
Processes a stereo image pair and returns the estimated pose.
| [in] | info | Tracking info with stereo images. |
| void Tracking::InformOnlyTracking | ( | bool | flag | ) |
Enables or disables localization-only tracking.
| [in] | flag | True for localization-only mode. |
| bool Tracking::parseCamParamFile | ( | const SLAMParameters & | params | ) |
Parses camera parameters from SLAM configuration.
| [in] | params | SLAM parameters. |
| bool Tracking::parseIMUParamFile | ( | const SLAMParameters & | params | ) |
Parses IMU parameters from SLAM configuration.
| [in] | params | SLAM parameters. |
| bool Tracking::parseORBParamFile | ( | const SLAMParameters & | params | ) |
Parses ORB extractor parameters from SLAM configuration.
| [in] | params | SLAM parameters. |
|
inline |
Returns the sensor configuration.
Definition at line 149 of file Tracking.h.
| void Tracking::SetLocalMapper | ( | LocalMapping * | pLocalMapper | ) |
Sets the local mapper reference.
| [in] | pLocalMapper | Pointer to the local mapper. |
| void Tracking::SetLoopClosing | ( | LoopClosing * | pLoopClosing | ) |
Sets the loop closer reference.
| [in] | pLoopClosing | Pointer to the loop closer. |
| void Tracking::setParams | ( | const SLAMParameters & | params | ) |
Updates SLAM parameters.
| [in] | params | New configuration parameters. |
|
inline |
Sets the tracking state.
| [in] | state | New tracking state. |
Definition at line 129 of file Tracking.h.
References state().
|
inline |
Returns the current tracking state.
Definition at line 125 of file Tracking.h.
Referenced by setState().
Updates frame IMU data after scale/bias refinement.
| [in] | scale | Refined scale factor. |
| [in] | b | Refined IMU bias. |
| [in] | pCurrentKeyFrame | Current keyframe. |