NDEVR
API Documentation
Map.h
1#pragma once
2#include "OrbSLAM/Headers/MapPoint.h"
3#include "OrbSLAM/Headers/KeyFrame.h"
4#include "Base/Headers/Dictionary.h"
5#include <mutex>
6
7
8namespace NDEVR
9{
10
11 class MapPoint;
12 class KeyFrame;
13 class Atlas;
14 class KeyFrameDatabase;
15 class InfoPipe;
21 class Map
22 {
23 public:
24 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
28 Map(LogPtr log);
33 Map(int initKFid, LogPtr log);
37 void updateID();
64
65 Buffer<KeyFrame*> GetAllKeyFrames() const;
66 Buffer<MapPoint*> GetAllMapPoints() const;
67 Buffer<MapPoint*> GetReferenceMapPoints() const;
68
69 uint04 MapPointsInMap() const;
70 uint04 KeyFramesInMap() const;
71
72 uint04 GetId() const
73 {
74 return mnId;
75 }
76
77 uint04 GetInitKFid() const;
78 uint04 GetMaxKFid() const;
79
80 KeyFrame* GetOriginKF() const;
81
82 void SetCurrentMap();
83 void SetStoredMap();
84 bool IsInUse();
85
86 void SetBad();
87 bool IsBad();
88 void clear();
89 int GetMapChangeIndex();
90 void IncreaseChangeIndex();
91 int GetLastMapChange();
92 void SetLastMapChange(int currentChangeId);
93 void SetImuInitialized();
94 bool isImuInitialized() const;
95
96 void ApplyScaledRotation(const Sophus::SE3f& T, const float s, const bool bScaledVel = false);
97
98 void SetInertialSensor(bool is_inertial);
99 bool IsInertial();
100 void SetIniertialBA1();
101 void SetIniertialBA2();
102 bool GetIniertialBA1();
103 bool GetIniertialBA2();
104 void ChangeId(uint04 nId);
105
106 uint04 GetLowerKFID();
107
108 LogPtr log() { return m_log; }
109 Buffer<KeyFrame*> mvpKeyFrameOrigins;
110 KeyFrame* mpFirstRegionKF = nullptr;
111 // Mutex
112 mutable std::mutex m_map_mutex;
113 std::mutex mMutexMapUpdate;
114
115 bool mbFail = false;
116
117
118 static uint04 nNextId;
119
120 // DEBUG: show KFs which are used in LBA
121#ifdef _DEBUG
122 Set<uint04> msOptKFs;
123 Set<uint04> msFixedKFs;
124#endif
125 protected:
126 LogPtr m_log;
127 uint04 mnId = 0U;
128 Set<MapPoint*> m_map_points;
129 Set<KeyFrame*> mspKeyFrames;
130 KeyFrame* mpKFinitial = nullptr;
131 KeyFrame* mpKFlowerID = nullptr;
132 Buffer<MapPoint*> mvpReferenceMapPoints;
133 int mnMapChange = 0;
134 int mnMapChangeNotified = 0;
135
136 uint04 mnInitKFid = 0U;
137 uint04 mnMaxKFid = 0U;
138 //long unsigned int mnLastLoopKFid;
139
140 // Index related to a big change in the map (loop closure, global BA)
141 int mnBigChangeIdx = 0;
142
143 bool mbImuInitialized = false;
144 bool mIsInUse = false;
145 bool mHasTumbnail = false;
146 bool mbBad = false;
147
148 bool mbIsInertial = false;
149 bool mbIMU_BA1 = false;
150 bool mbIMU_BA2 = false;
151
152
153 };
154
155}
Manages a collection of maps for the ORB-SLAM system.
Definition Atlas.h:29
The equivelent of std::vector but with a bit more control.
Definition Buffer.hpp:58
A light-weight base class for Log that allows processes to update, without the need for additional in...
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
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Map(LogPtr log)
Constructs an empty map.
Map(int initKFid, LogPtr log)
Constructs a map with an initial keyframe ID.
void updateID()
Updates the map ID.
void InformNewBigChange()
Signals that a big change has occurred (e.g.
int GetLastBigChangeIdx()
Returns the index of the last big change.
void EraseMapPoint(MapPoint *pMP)
Removes a map point from the map.
void AddMapPoint(MapPoint *pMP)
Adds a map point to the map.
void SetReferenceMapPoints(const Buffer< MapPoint * > &vpMPs)
Sets the reference map points.
~Map()
Destructor.
void AddKeyFrame(KeyFrame *pKF)
Adds a keyframe to the map.
void EraseKeyFrame(KeyFrame *pKF)
Removes a keyframe from the map.
The primary namespace for the NDEVR SDK.
uint32_t uint04
-Defines an alias representing a 4 byte, unsigned integer -Can represent exact integer values 0 throu...