NDEVR
API Documentation
OrbSLAM

Main entry point for the ORB-SLAM3 system. More...

Public Member Functions

 OrbSLAM (const File &vocab, const SLAMParameters &params, LogPtr log)
 Constructs and initializes the SLAM system with a vocabulary file.
 OrbSLAM (const SLAMParameters &params, LogPtr log)
 Constructs and initializes the SLAM system without a vocabulary file.
void ActivateLocalizationMode ()
 Activates localization-only mode (stops map building).
void ChangeDataset ()
 Signals a dataset change for multi-sequence operation.
uint04 CurrentMapID () const
 Returns the current map ID.
void DeactivateLocalizationMode ()
 Deactivates localization-only mode (resumes SLAM).
Buffer< KeyFrame * > getAllKeyFrames () const
 Returns all keyframes across all maps.
Buffer< Sophus::SE3f > getAllKeyFramesAfter (uint04 index) const
 Returns keyframe poses after a given index.
double GetTimeFromIMUInit ()
 Returns the time elapsed since IMU initialization.
Buffer< MapPoint * > GetTrackedMapPoints ()
 Returns the tracked map points from the most recent frame.
Tracking::eTrackingState GetTrackingState ()
 Returns the current tracking state.
void init (const File &vocab, const SLAMParameters &params)
 Initializes the system with a vocabulary file and parameters.
bool isShutDown ()
 Checks whether the system has been shut down.
const KeyFramelastKeyFrame () const
 Returns the last processed keyframe.
bool MapChanged ()
 Checks whether the map has changed since the last call.
bool needsMapReset () const
 Checks whether the map needs to be reset.
void reset ()
 Resets the entire system, clearing the Atlas.
void ResetActiveMap ()
 Resets only the active map.
void setParams (const SLAMParameters &params)
 Updates the SLAM configuration parameters.
void Shutdown ()
 Shuts down all threads and waits for them to finish.
Sophus::SE3f TrackMonocular (OrbTrackingInfo &info)
 Processes a monocular frame and returns the estimated camera pose.
Sophus::SE3f TrackRGBD (OrbTrackingInfo &info)
 Processes an RGB-D frame and returns the estimated camera pose.
Sophus::SE3f TrackStereo (OrbTrackingInfo &info)
 Processes a stereo frame and returns the estimated camera pose.
void updateInfo (const Matrix< fltp08 > &global_offset, DesignObjectLookup *lookup, const Model &frame_model, const Matrix< fltp08 > &frame_model_transform, bool show_keyframes, bool show_map_points)
 Updates the visualization models with current SLAM data.

Detailed Description

Main entry point for the ORB-SLAM3 system.

Manages the tracking, local mapping, and loop closing threads. Provides methods to process stereo, RGB-D, and monocular frames, and to query system state.

Definition at line 36 of file System.h.

Constructor & Destructor Documentation

◆ OrbSLAM() [1/2]

OrbSLAM::OrbSLAM ( const SLAMParameters & params,
LogPtr log )

Constructs and initializes the SLAM system without a vocabulary file.

Parameters
[in]paramsSLAM configuration parameters.
[in]logLogger for diagnostic output.

◆ OrbSLAM() [2/2]

OrbSLAM::OrbSLAM ( const File & vocab,
const SLAMParameters & params,
LogPtr log )

Constructs and initializes the SLAM system with a vocabulary file.

Parameters
[in]vocabPath to the ORB vocabulary file.
[in]paramsSLAM configuration parameters.
[in]logLogger for diagnostic output.

Member Function Documentation

◆ CurrentMapID()

uint04 OrbSLAM::CurrentMapID ( ) const

Returns the current map ID.

Returns
The map ID.

◆ getAllKeyFrames()

Buffer< KeyFrame * > OrbSLAM::getAllKeyFrames ( ) const

Returns all keyframes across all maps.

Returns
Buffer of keyframe pointers.

◆ getAllKeyFramesAfter()

Buffer< Sophus::SE3f > OrbSLAM::getAllKeyFramesAfter ( uint04 index) const

Returns keyframe poses after a given index.

Parameters
[in]indexMinimum keyframe ID to include.
Returns
Buffer of SE3 poses.

◆ GetTimeFromIMUInit()

double OrbSLAM::GetTimeFromIMUInit ( )

Returns the time elapsed since IMU initialization.

Returns
Time in seconds.

◆ GetTrackedMapPoints()

Buffer< MapPoint * > OrbSLAM::GetTrackedMapPoints ( )

Returns the tracked map points from the most recent frame.

Returns
Buffer of tracked map point pointers.

◆ GetTrackingState()

Tracking::eTrackingState OrbSLAM::GetTrackingState ( )

Returns the current tracking state.

Returns
The tracking state enum value.

◆ init()

void OrbSLAM::init ( const File & vocab,
const SLAMParameters & params )

Initializes the system with a vocabulary file and parameters.

Parameters
[in]vocabPath to the ORB vocabulary file.
[in]paramsSLAM configuration parameters.

◆ isShutDown()

bool OrbSLAM::isShutDown ( )

Checks whether the system has been shut down.

Returns
True if shut down.

◆ lastKeyFrame()

const KeyFrame * OrbSLAM::lastKeyFrame ( ) const

Returns the last processed keyframe.

Returns
Pointer to the last keyframe.

◆ MapChanged()

bool OrbSLAM::MapChanged ( )

Checks whether the map has changed since the last call.

Returns
True if a big map change occurred (loop closure, global BA).

◆ needsMapReset()

bool OrbSLAM::needsMapReset ( ) const

Checks whether the map needs to be reset.

Returns
True if a map reset is needed.

◆ setParams()

void OrbSLAM::setParams ( const SLAMParameters & params)

Updates the SLAM configuration parameters.

Parameters
[in]paramsNew configuration parameters.

◆ TrackMonocular()

Sophus::SE3f OrbSLAM::TrackMonocular ( OrbTrackingInfo & info)

Processes a monocular frame and returns the estimated camera pose.

Parameters
[in]infoTracking info containing the monocular image.
Returns
The estimated camera pose (empty if tracking fails).

◆ TrackRGBD()

Sophus::SE3f OrbSLAM::TrackRGBD ( OrbTrackingInfo & info)

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

Parameters
[in]infoTracking info containing color and depth images.
Returns
The estimated camera pose (empty if tracking fails).

◆ TrackStereo()

Sophus::SE3f OrbSLAM::TrackStereo ( OrbTrackingInfo & info)

Processes a stereo frame and returns the estimated camera pose.

Parameters
[in]infoTracking info containing stereo images and metadata.
Returns
The estimated camera pose (empty if tracking fails).

◆ updateInfo()

void OrbSLAM::updateInfo ( const Matrix< fltp08 > & global_offset,
DesignObjectLookup * lookup,
const Model & frame_model,
const Matrix< fltp08 > & frame_model_transform,
bool show_keyframes,
bool show_map_points )

Updates the visualization models with current SLAM data.

Parameters
[in]global_offsetGlobal coordinate offset matrix.
[in]lookupDesign object lookup.
[in]frame_modelModel representing the current frame.
[in]frame_model_transformTransform for the frame model.
[in]show_keyframesWhether to show keyframes.
[in]show_map_pointsWhether to show map points.

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