![]() |
NDEVR
API Documentation
|
Manages a collection of maps for the ORB-SLAM system. More...
Public Member Functions | |
| Atlas (int initKFid, LogPtr log) | |
| Constructs an Atlas and creates the first map. | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | Atlas (LogPtr log) |
| Constructs an Atlas with a logger. | |
| ~Atlas () | |
| Destructor. | |
| GeometricCamera * | AddCamera (GeometricCamera *pCam) |
| Adds a camera model, returning an existing one if equal. | |
| void | AddKeyFrame (KeyFrame *pKF) |
| Adds a keyframe to the current map. | |
| void | AddMapPoint (MapPoint *pMP) |
| Adds a map point to the current map. | |
| void | ChangeMap (Map *pMap) |
| Switches the current active map. | |
| void | clearAtlas () |
| Clears the entire Atlas, removing all maps and data. | |
| void | clearMap () |
| Clears the current map. | |
| uint04 | CountMaps () |
| Returns the number of maps in this Atlas. | |
| Map * | createNewMap () |
| Creates a new map and sets it as the current map. | |
| Map * | currentMapPtr () |
| Returns a pointer to the current active map. | |
| Buffer< GeometricCamera * > | GetAllCameras () |
| Returns all registered cameras. | |
| Buffer< KeyFrame * > | GetAllKeyFrames () |
| Returns all keyframes in the current map. | |
| Buffer< MapPoint * > | GetAllMapPoints () |
| Returns all map points in the current map. | |
| Buffer< Map * > | GetAllMaps () |
| Returns all maps managed by this Atlas. | |
| KeyFrameDatabase * | GetKeyFrameDatabase () |
| Returns the keyframe database. | |
| int | GetLastBigChangeIdx () |
| Returns the index of the last big change in the current map. | |
| uint04 | GetLastInitKFid () |
| Returns the last initial keyframe ID across all maps. | |
| ORBVocabulary * | GetORBVocabulary () |
| Returns the ORB vocabulary. | |
| Buffer< MapPoint * > | GetReferenceMapPoints () |
| Returns the reference map points in the current map. | |
| void | InformNewBigChange () |
| Signals that a big change (e.g. | |
| bool | isImuInitialized () |
| Checks whether the IMU has been initialized for the current map. | |
| bool | isInertial () |
| Checks whether the current map uses an inertial sensor. | |
| uint04 | KeyFramesInMap () |
| Returns the number of keyframes in the current map. | |
| uint04 | MapPointsInMap () |
| Returns the number of map points in the current map. | |
| void | RemoveBadMaps () |
| Removes all maps that have been marked as bad. | |
| void | SetImuInitialized () |
| Marks the IMU as initialized for the current map. | |
| void | SetInertialSensor (bool is_inertial) |
| Sets whether the current map uses an inertial sensor. | |
| void | SetKeyFrameDababase (KeyFrameDatabase *pKFDB) |
| Sets the keyframe database used for place recognition. | |
| void | SetMapBad (Map *pMap) |
| Marks a map as bad and moves it to the bad maps list. | |
| void | SetORBVocabulary (ORBVocabulary *pORBVoc) |
| Sets the ORB vocabulary for feature matching. | |
| void | SetReferenceMapPoints (const Buffer< MapPoint * > &vpMPs) |
| Sets the reference map points for the current map. | |
Protected Attributes | |
| LogPtr | m_log = nullptr |
| Logger instance. | |
| std::mutex | mMutexAtlas |
| Mutex protecting Atlas state. | |
| uint04 | mnLastInitKFidMap = 0U |
| Last initial keyframe ID across maps. | |
| Map * | mpCurrentMap = nullptr |
| Currently active map. | |
| KeyFrameDatabase * | mpKeyFrameDB = nullptr |
| Keyframe database for place recognition. | |
| ORBVocabulary * | mpORBVocabulary = nullptr |
| ORB vocabulary for feature matching. | |
| Buffer< Map * > | mspBadMaps |
| Maps marked as bad. | |
| Buffer< Map * > | mspMaps |
| All active maps. | |
| Buffer< GeometricCamera * > | mvpCameras |
| Registered camera models. | |
Manages a collection of maps for the ORB-SLAM system.
The Atlas holds multiple maps, tracks the current active map, and provides methods for adding/removing keyframes, map points, and cameras across maps.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW Atlas::Atlas | ( | LogPtr | log | ) |
Constructs an Atlas with a logger.
| [in] | log | Logger for diagnostic output. |
| Atlas::Atlas | ( | int | initKFid, |
| LogPtr | log ) |
Constructs an Atlas and creates the first map.
| [in] | initKFid | Initial keyframe ID for the first map. |
| [in] | log | Logger for diagnostic output. |
| GeometricCamera * Atlas::AddCamera | ( | GeometricCamera * | pCam | ) |
| void Atlas::AddKeyFrame | ( | KeyFrame * | pKF | ) |
Adds a keyframe to the current map.
| [in] | pKF | Pointer to the keyframe to add. |
| void Atlas::AddMapPoint | ( | MapPoint * | pMP | ) |
Adds a map point to the current map.
| [in] | pMP | Pointer to the map point to add. |
| void Atlas::ChangeMap | ( | Map * | pMap | ) |
Switches the current active map.
| [in] | pMap | Pointer to the map to activate. |
| Map * Atlas::createNewMap | ( | ) |
Creates a new map and sets it as the current map.
| Map * Atlas::currentMapPtr | ( | ) |
Returns a pointer to the current active map.
| Buffer< GeometricCamera * > Atlas::GetAllCameras | ( | ) |
Returns all registered cameras.
Returns all keyframes in the current map.
Returns all map points in the current map.
| KeyFrameDatabase * Atlas::GetKeyFrameDatabase | ( | ) |
Returns the keyframe database.
| int Atlas::GetLastBigChangeIdx | ( | ) |
Returns the index of the last big change in the current map.
| uint04 Atlas::GetLastInitKFid | ( | ) |
Returns the last initial keyframe ID across all maps.
| ORBVocabulary * Atlas::GetORBVocabulary | ( | ) |
Returns the ORB vocabulary.
Returns the reference map points in the current map.
| void Atlas::InformNewBigChange | ( | ) |
Signals that a big change (e.g.
loop closure) has occurred in the current map.
| bool Atlas::isImuInitialized | ( | ) |
Checks whether the IMU has been initialized for the current map.
| bool Atlas::isInertial | ( | ) |
Checks whether the current map uses an inertial sensor.
| uint04 Atlas::KeyFramesInMap | ( | ) |
Returns the number of keyframes in the current map.
| uint04 Atlas::MapPointsInMap | ( | ) |
Returns the number of map points in the current map.
| void Atlas::SetInertialSensor | ( | bool | is_inertial | ) |
Sets whether the current map uses an inertial sensor.
| [in] | is_inertial | True to enable inertial mode. |
| void Atlas::SetKeyFrameDababase | ( | KeyFrameDatabase * | pKFDB | ) |
Sets the keyframe database used for place recognition.
| [in] | pKFDB | Pointer to the keyframe database. |
| void Atlas::SetMapBad | ( | Map * | pMap | ) |
Marks a map as bad and moves it to the bad maps list.
| [in] | pMap | Pointer to the map to mark as bad. |
| void Atlas::SetORBVocabulary | ( | ORBVocabulary * | pORBVoc | ) |
Sets the ORB vocabulary for feature matching.
| [in] | pORBVoc | Pointer to the ORB vocabulary. |
Sets the reference map points for the current map.
| [in] | vpMPs | Buffer of reference map point pointers. |