NDEVR
API Documentation
Tracking

Main tracking thread that processes each frame and estimates camera pose. More...

Collaboration diagram for Tracking:
[legend]

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 &params, 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.
KeyFrameGetLastKeyFrame ()
 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 &params)
 Parses camera parameters from SLAM configuration.
bool parseIMUParamFile (const SLAMParameters &params)
 Parses IMU parameters from SLAM configuration.
bool parseORBParamFile (const SLAMParameters &params)
 Parses ORB extractor parameters from SLAM configuration.
const Sensorsensor () 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 &params)
 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.

Detailed Description

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.

Member Enumeration Documentation

◆ eTrackingState

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.

◆ GlobalFrameAlignmentState

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.

Constructor & Destructor Documentation

◆ Tracking()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Tracking::Tracking ( OrbSLAM * pSys,
ORBVocabulary * pVoc,
Atlas * pAtlas,
KeyFrameDatabase * pKFDB,
const SLAMParameters & params,
LogPtr log )

Constructs the tracker.

Parameters
[in]pSysPointer to the OrbSLAM system.
[in]pVocORB vocabulary.
[in]pAtlasPointer to the Atlas.
[in]pKFDBKeyframe database for place recognition.
[in]paramsSLAM configuration parameters.
[in]logLogger for diagnostic output.

Member Function Documentation

◆ appendGPSData()

void Tracking::appendGPSData ( const Buffer< GlobalPosition * > gps_measurements,
fltp08 time_offset )

Appends GPS measurements to the processing queue.

Parameters
[in]gps_measurementsBuffer of GPS data points.
[in]time_offsetTime offset to apply.

◆ appendImuData()

void Tracking::appendImuData ( Buffer< IMU::Point > imu_measurements,
fltp08 time_offset )

Appends IMU measurements to the processing queue.

Parameters
[in]imu_measurementsBuffer of IMU data points.
[in]time_offsetTime offset to apply.

◆ ensureValidData()

bool Tracking::ensureValidData ( const cv::Mat & imRectLeft) const

Validates that the input image data is usable.

Parameters
[in]imRectLeftThe left/main rectified image.
Returns
True if the data is valid.

◆ GetLastKeyFrame()

KeyFrame * Tracking::GetLastKeyFrame ( )
inline

Returns the last keyframe.

Returns
Pointer to the last keyframe.

Definition at line 145 of file Tracking.h.

◆ GetMatchesInliers()

int Tracking::GetMatchesInliers ( )
inline

Returns the number of inlier matches in the current frame.

Returns
Inlier match count.

Definition at line 155 of file Tracking.h.

◆ GrabImageMonocular()

Sophus::SE3f Tracking::GrabImageMonocular ( OrbTrackingInfo & info)

Processes a monocular image and returns the estimated pose.

Parameters
[in]infoTracking info with the monocular image.
Returns
The estimated camera pose.

◆ GrabImageRGBD()

Sophus::SE3f Tracking::GrabImageRGBD ( OrbTrackingInfo & info)

Processes an RGB-D frame and returns the estimated pose.

Parameters
[in]infoTracking info with color and depth images.
Returns
The estimated camera pose.

◆ GrabImageStereo()

Sophus::SE3f Tracking::GrabImageStereo ( OrbTrackingInfo & info)

Processes a stereo image pair and returns the estimated pose.

Parameters
[in]infoTracking info with stereo images.
Returns
The estimated camera pose.

◆ InformOnlyTracking()

void Tracking::InformOnlyTracking ( bool flag)

Enables or disables localization-only tracking.

Parameters
[in]flagTrue for localization-only mode.

◆ parseCamParamFile()

bool Tracking::parseCamParamFile ( const SLAMParameters & params)

Parses camera parameters from SLAM configuration.

Parameters
[in]paramsSLAM parameters.
Returns
True if parsing succeeded.

◆ parseIMUParamFile()

bool Tracking::parseIMUParamFile ( const SLAMParameters & params)

Parses IMU parameters from SLAM configuration.

Parameters
[in]paramsSLAM parameters.
Returns
True if parsing succeeded.

◆ parseORBParamFile()

bool Tracking::parseORBParamFile ( const SLAMParameters & params)

Parses ORB extractor parameters from SLAM configuration.

Parameters
[in]paramsSLAM parameters.
Returns
True if parsing succeeded.

◆ sensor()

const Sensor & Tracking::sensor ( ) const
inline

Returns the sensor configuration.

Returns
Reference to the sensor config.

Definition at line 149 of file Tracking.h.

◆ SetLocalMapper()

void Tracking::SetLocalMapper ( LocalMapping * pLocalMapper)

Sets the local mapper reference.

Parameters
[in]pLocalMapperPointer to the local mapper.

◆ SetLoopClosing()

void Tracking::SetLoopClosing ( LoopClosing * pLoopClosing)

Sets the loop closer reference.

Parameters
[in]pLoopClosingPointer to the loop closer.

◆ setParams()

void Tracking::setParams ( const SLAMParameters & params)

Updates SLAM parameters.

Parameters
[in]paramsNew configuration parameters.

◆ setState()

void Tracking::setState ( eTrackingState state)
inline

Sets the tracking state.

Parameters
[in]stateNew tracking state.

Definition at line 129 of file Tracking.h.

References state().

◆ state()

eTrackingState Tracking::state ( ) const
inline

Returns the current tracking state.

Returns
The tracking state.

Definition at line 125 of file Tracking.h.

Referenced by setState().

◆ UpdateFrameIMU()

void Tracking::UpdateFrameIMU ( fltp04 scale,
const IMU::Bias & b,
KeyFrame * pCurrentKeyFrame )

Updates frame IMU data after scale/bias refinement.

Parameters
[in]scaleRefined scale factor.
[in]bRefined IMU bias.
[in]pCurrentKeyFrameCurrent keyframe.

The documentation for this class was generated from the following file: