NDEVR
API Documentation
Atlas.h
1#pragma once
2#include "OrbSLAM/Headers/Map.h"
3#include "OrbSLAM/Headers/MapPoint.h"
4#include "OrbSLAM/Headers/KeyFrame.h"
5#include "GraphOptimization/Headers/GeometricCamera.h"
6#include "Base/Headers/Dictionary.h"
7#include "Base/Headers/Set.h"
8#include <NDEVR/DynamicPointer.h>
9#include <mutex>
10
11
12namespace NDEVR
13{
14 class Viewer;
15 class Map;
16 class MapPoint;
17 class KeyFrame;
18 class KeyFrameDatabase;
19 class Frame;
20 class KannalaBrandt8;
21 class Pinhole;
22
28 class Atlas
29 {
30
31 public:
32 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
33
42 Atlas(int initKFid, LogPtr log);
45
53 void ChangeMap(Map* pMap);
54
59
68 //void EraseMapPoint(MapPoint* pMP);
69 //void EraseKeyFrame(KeyFrame* pKF);
70
80
91
100
113
118
123
125 void clearMap();
126
129
137 void SetMapBad(Map* pMap);
140
148 void SetInertialSensor(bool is_inertial);
155
164
173 protected:
174
178 Map* mpCurrentMap = nullptr;
180
181
184
185 std::mutex mMutexAtlas;
186 LogPtr m_log = nullptr;
187
188 }; // class Atlas
189
190}
Map * mpCurrentMap
Currently active map.
Definition Atlas.h:178
LogPtr m_log
Logger instance.
Definition Atlas.h:186
void AddKeyFrame(KeyFrame *pKF)
Adds a keyframe to the current map.
void SetMapBad(Map *pMap)
Marks a map as bad and moves it to the bad maps list.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Atlas(LogPtr log)
Constructs an Atlas with a logger.
bool isInertial()
Checks whether the current map uses an inertial sensor.
GeometricCamera * AddCamera(GeometricCamera *pCam)
Adds a camera model, returning an existing one if equal.
void clearAtlas()
Clears the entire Atlas, removing all maps and data.
uint04 KeyFramesInMap()
Returns the number of keyframes in the current map.
uint04 CountMaps()
Returns the number of maps in this Atlas.
uint04 mnLastInitKFidMap
Last initial keyframe ID across maps.
Definition Atlas.h:179
std::mutex mMutexAtlas
Mutex protecting Atlas state.
Definition Atlas.h:185
Atlas(int initKFid, LogPtr log)
Constructs an Atlas and creates the first map.
Buffer< GeometricCamera * > GetAllCameras()
Returns all registered cameras.
void RemoveBadMaps()
Removes all maps that have been marked as bad.
KeyFrameDatabase * GetKeyFrameDatabase()
Returns the keyframe database.
Buffer< GeometricCamera * > mvpCameras
Registered camera models.
Definition Atlas.h:177
void SetInertialSensor(bool is_inertial)
Sets whether the current map uses an inertial sensor.
void SetReferenceMapPoints(const Buffer< MapPoint * > &vpMPs)
Sets the reference map points for the current map.
Buffer< MapPoint * > GetAllMapPoints()
Returns all map points in the current map.
Buffer< KeyFrame * > GetAllKeyFrames()
Returns all keyframes in the current map.
void SetKeyFrameDababase(KeyFrameDatabase *pKFDB)
Sets the keyframe database used for place recognition.
~Atlas()
Destructor.
void SetORBVocabulary(ORBVocabulary *pORBVoc)
Sets the ORB vocabulary for feature matching.
Map * createNewMap()
Creates a new map and sets it as the current map.
int GetLastBigChangeIdx()
Returns the index of the last big change in the current map.
Map * currentMapPtr()
Returns a pointer to the current active map.
void clearMap()
Clears the current map.
KeyFrameDatabase * mpKeyFrameDB
Keyframe database for place recognition.
Definition Atlas.h:182
ORBVocabulary * GetORBVocabulary()
Returns the ORB vocabulary.
void AddMapPoint(MapPoint *pMP)
Adds a map point to the current map.
void ChangeMap(Map *pMap)
Switches the current active map.
bool isImuInitialized()
Checks whether the IMU has been initialized for the current map.
Buffer< Map * > GetAllMaps()
Returns all maps managed by this Atlas.
void InformNewBigChange()
Signals that a big change (e.g.
uint04 MapPointsInMap()
Returns the number of map points in the current map.
Buffer< MapPoint * > GetReferenceMapPoints()
Returns the reference map points in the current map.
Buffer< Map * > mspMaps
All active maps.
Definition Atlas.h:175
ORBVocabulary * mpORBVocabulary
ORB vocabulary for feature matching.
Definition Atlas.h:183
uint04 GetLastInitKFid()
Returns the last initial keyframe ID across all maps.
void SetImuInitialized()
Marks the IMU as initialized for the current map.
Buffer< Map * > mspBadMaps
Maps marked as bad.
Definition Atlas.h:176
The equivelent of std::vector but with a bit more control.
Definition Buffer.hpp:58
Represents a single image frame with extracted features and pose information.
Definition Frame.h:111
Abstract interface for geometric camera models (pinhole, fisheye, etc.).
Database of keyframes for place recognition and relocalization.
A keyframe in the SLAM map, derived from Frame.
Definition KeyFrame.h:31
A light-weight wrapper that will be a no-op if there is not a valid log reference,...
A 3D point in the SLAM map observed by multiple keyframes.
Definition MapPoint.h:24
Represents a single SLAM map containing keyframes and map points.
Definition Map.h:22
The primary namespace for the NDEVR SDK.
TemplatedVocabulary< FORB::TDescriptor, FORB > ORBVocabulary
ORB visual vocabulary type for Bag-of-Words place recognition.
uint32_t uint04
-Defines an alias representing a 4 byte, unsigned integer -Can represent exact integer values 0 throu...