![]() |
NDEVR
API Documentation
|
Main entry point for the ORB-SLAM3 system. More...
Public Member Functions | |
| OrbSLAM (const File &vocab, const SLAMParameters ¶ms, LogPtr log) | |
| Constructs and initializes the SLAM system with a vocabulary file. | |
| OrbSLAM (const SLAMParameters ¶ms, 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 ¶ms) |
| Initializes the system with a vocabulary file and parameters. | |
| bool | isShutDown () |
| Checks whether the system has been shut down. | |
| const KeyFrame * | lastKeyFrame () 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 ¶ms) |
| 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. | |
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.
| OrbSLAM::OrbSLAM | ( | const SLAMParameters & | params, |
| LogPtr | log ) |
Constructs and initializes the SLAM system without a vocabulary file.
| [in] | params | SLAM configuration parameters. |
| [in] | log | Logger for diagnostic output. |
| OrbSLAM::OrbSLAM | ( | const File & | vocab, |
| const SLAMParameters & | params, | ||
| LogPtr | log ) |
Constructs and initializes the SLAM system with a vocabulary file.
| [in] | vocab | Path to the ORB vocabulary file. |
| [in] | params | SLAM configuration parameters. |
| [in] | log | Logger for diagnostic output. |
| uint04 OrbSLAM::CurrentMapID | ( | ) | const |
Returns the current map ID.
Returns all keyframes across all maps.
Returns keyframe poses after a given index.
| [in] | index | Minimum keyframe ID to include. |
| double OrbSLAM::GetTimeFromIMUInit | ( | ) |
Returns the time elapsed since IMU initialization.
Returns the tracked map points from the most recent frame.
| Tracking::eTrackingState OrbSLAM::GetTrackingState | ( | ) |
Returns the current tracking state.
| void OrbSLAM::init | ( | const File & | vocab, |
| const SLAMParameters & | params ) |
Initializes the system with a vocabulary file and parameters.
| [in] | vocab | Path to the ORB vocabulary file. |
| [in] | params | SLAM configuration parameters. |
| bool OrbSLAM::isShutDown | ( | ) |
Checks whether the system has been shut down.
| const KeyFrame * OrbSLAM::lastKeyFrame | ( | ) | const |
Returns the last processed keyframe.
| bool OrbSLAM::MapChanged | ( | ) |
Checks whether the map has changed since the last call.
| bool OrbSLAM::needsMapReset | ( | ) | const |
Checks whether the map needs to be reset.
| void OrbSLAM::setParams | ( | const SLAMParameters & | params | ) |
Updates the SLAM configuration parameters.
| [in] | params | New configuration parameters. |
| Sophus::SE3f OrbSLAM::TrackMonocular | ( | OrbTrackingInfo & | info | ) |
Processes a monocular frame and returns the estimated camera pose.
| [in] | info | Tracking info containing the monocular image. |
| Sophus::SE3f OrbSLAM::TrackRGBD | ( | OrbTrackingInfo & | info | ) |
Processes an RGB-D frame and returns the estimated camera pose.
| [in] | info | Tracking info containing color and depth images. |
| Sophus::SE3f OrbSLAM::TrackStereo | ( | OrbTrackingInfo & | info | ) |
Processes a stereo frame and returns the estimated camera pose.
| [in] | info | Tracking info containing stereo images and metadata. |
| 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.
| [in] | global_offset | Global coordinate offset matrix. |
| [in] | lookup | Design object lookup. |
| [in] | frame_model | Model representing the current frame. |
| [in] | frame_model_transform | Transform for the frame model. |
| [in] | show_keyframes | Whether to show keyframes. |
| [in] | show_map_points | Whether to show map points. |