Overview
The Atlas class is ORB-SLAM3’s multi-map management system. It maintains a collection of Map instances, manages the active map, handles map creation and switching, and supports map merging operations. The Atlas enables robust operation in scenarios with tracking failures and relocalization by maintaining multiple independent maps.
namespace ORB_SLAM3 {
class Atlas;
}
Defined in: Atlas.h:49
Key Features
- Multi-map storage and management
- Active map switching and selection
- Map creation on tracking failure
- Map merging when loop closure detected between maps
- Camera calibration management
- Global ID management for Frame, KeyFrame, MapPoint
- Map serialization and loading support
Constructors
Default Constructor
Creates an empty Atlas.
Constructor with Initial KeyFrame ID
Creates an Atlas and initializes the first map.
Parameters:
initKFid - Initial KeyFrame ID for the first map
Map Management
CreateNewMap
Creates and activates a new map. Called when tracking is lost and cannot be recovered.
ChangeMap
void ChangeMap(Map* pMap);
Switches the active map to the specified map.
Parameters:
GetCurrentMap
Returns a pointer to the currently active map.
GetAllMaps
vector<Map*> GetAllMaps();
Returns all maps in the Atlas.
CountMaps
Returns the number of maps in the Atlas.
SetMapBad
void SetMapBad(Map* pMap);
Marks a map as bad (to be deleted).
RemoveBadMaps
Removes all maps marked as bad from the Atlas.
clearMap
Clears the current map.
clearAtlas
Clears all maps from the Atlas.
Adding Elements to Current Map
These methods operate on the currently active map.
AddKeyFrame
void AddKeyFrame(KeyFrame* pKF);
Adds a KeyFrame to the current map.
AddMapPoint
void AddMapPoint(MapPoint* pMP);
Adds a MapPoint to the current map.
SetReferenceMapPoints
void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
Sets the reference MapPoints for the current map.
Querying Current Map
GetAllKeyFrames
std::vector<KeyFrame*> GetAllKeyFrames();
Returns all KeyFrames in the current map.
GetAllMapPoints
std::vector<MapPoint*> GetAllMapPoints();
Returns all MapPoints in the current map.
GetReferenceMapPoints
std::vector<MapPoint*> GetReferenceMapPoints();
Returns the reference MapPoints of the current map.
KeyFramesInMap
long unsigned KeyFramesInMap();
Returns the number of KeyFrames in the current map.
MapPointsInMap
long unsigned int MapPointsInMap();
Returns the number of MapPoints in the current map.
Global Queries
GetAtlasKeyframes
map<long unsigned int, KeyFrame*> GetAtlasKeyframes();
Returns all KeyFrames from all maps indexed by ID.
GetNumLivedKF
long unsigned int GetNumLivedKF();
Returns the total number of KeyFrames across all maps.
GetNumLivedMP
long unsigned int GetNumLivedMP();
Returns the total number of MapPoints across all maps.
Map Change Tracking
void InformNewBigChange();
Notifies that a big change occurred in the current map (loop closure, global BA).
GetLastBigChangeIdx
int GetLastBigChangeIdx();
Returns the index of the last big change in the current map.
GetLastInitKFid
unsigned long int GetLastInitKFid();
Returns the initial KeyFrame ID of the last created map.
Camera Management
AddCamera
GeometricCamera* AddCamera(GeometricCamera* pCam);
Adds a camera to the Atlas and returns pointer to it (or existing camera if already present).
GetAllCameras
std::vector<GeometricCamera*> GetAllCameras();
Returns all cameras registered in the Atlas.
The Atlas stores unique camera instances to avoid duplication and ensure consistent calibration across maps.
Inertial SLAM
isInertial
Returns true if the current map uses inertial sensor.
SetInertialSensor
void SetInertialSensor();
Marks the current map as using inertial sensor.
SetImuInitialized
void SetImuInitialized();
Marks IMU as initialized for the current map.
isImuInitialized
Returns true if IMU is initialized in the current map.
Visualization
SetViewer
void SetViewer(Viewer* pViewer);
Sets the viewer for map visualization.
Database and Vocabulary
SetKeyFrameDababase
void SetKeyFrameDababase(KeyFrameDatabase* pKFDB);
Sets the KeyFrame database used for place recognition.
GetKeyFrameDatabase
KeyFrameDatabase* GetKeyFrameDatabase();
Returns the KeyFrame database.
SetORBVocabulary
void SetORBVocabulary(ORBVocabulary* pORBVoc);
Sets the ORB vocabulary for Bag-of-Words.
GetORBVocabulary
ORBVocabulary* GetORBVocabulary();
Returns the ORB vocabulary.
Serialization
PreSave
Prepares the Atlas for serialization (saves current state).
PostLoad
Restores the Atlas after deserialization.
The Atlas serialization includes all maps, KeyFrames, MapPoints, and their relationships, enabling save/load functionality.
Data Members
Map Storage
// Current active map
Map* mpCurrentMap;
// All maps
std::set<Map*> mspMaps;
// Bad maps pending deletion
std::set<Map*> mspBadMaps;
// Backup for serialization
std::vector<Map*> mvpBackupMaps;
Camera Storage
// All cameras in the system
std::vector<GeometricCamera*> mvpCameras;
Global IDs
// Last initialized KeyFrame ID for map creation
unsigned long int mnLastInitKFidMap;
// Static IDs are managed through serialization:
// - Map::nNextId
// - Frame::nNextId
// - KeyFrame::nNextId
// - MapPoint::nNextId
// - GeometricCamera::nNextId
References
// Viewer for visualization
Viewer* mpViewer;
bool mHasViewer;
// Database and vocabulary
KeyFrameDatabase* mpKeyFrameDB;
ORBVocabulary* mpORBVocabulary;
Thread Safety
Usage Example
// Create Atlas
Atlas* pAtlas = new Atlas(0);
// Set vocabulary and database
pAtlas->SetORBVocabulary(pVocabulary);
pAtlas->SetKeyFrameDababase(pKFDB);
// Add camera
GeometricCamera* pCamera = new Pinhole(params);
pAtlas->AddCamera(pCamera);
// Add elements to current map
pAtlas->AddKeyFrame(pKF);
pAtlas->AddMapPoint(pMP);
// Get current map info
Map* pCurrentMap = pAtlas->GetCurrentMap();
std::cout << "Current map has "
<< pAtlas->KeyFramesInMap() << " KeyFrames" << std::endl;
// Create new map if tracking lost
if (trackingLost) {
pAtlas->CreateNewMap();
std::cout << "Created new map. Total maps: "
<< pAtlas->CountMaps() << std::endl;
}
// Get all KeyFrames from all maps
map<long unsigned int, KeyFrame*> allKFs = pAtlas->GetAtlasKeyframes();
std::cout << "Total KeyFrames in Atlas: "
<< pAtlas->GetNumLivedKF() << std::endl;
Map Creation Strategy
The Atlas creates new maps in these scenarios:
- Initial startup - First map is created during Atlas construction
- Tracking failure - When tracking cannot be recovered and relocalization fails
- Map merging - When loop closure is detected between different maps, they can be merged
The multi-map architecture makes ORB-SLAM3 more robust than single-map systems. If tracking is lost, a new map is created instead of failing completely. Maps can later be merged when loops are detected.
Thread Safety Considerations
The Atlas uses a single mutex for thread safety:
- All map operations should be protected
- Camera additions are thread-safe
- Current map pointer access is protected