2#include "OrbSLAM/Headers/MapPoint.h"
3#include "OrbSLAM/Headers/KeyFrame.h"
4#include "Base/Headers/Dictionary.h"
24 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
69 uint04 MapPointsInMap()
const;
70 uint04 KeyFramesInMap()
const;
77 uint04 GetInitKFid()
const;
89 int GetMapChangeIndex();
90 void IncreaseChangeIndex();
91 int GetLastMapChange();
92 void SetLastMapChange(
int currentChangeId);
93 void SetImuInitialized();
94 bool isImuInitialized()
const;
96 void ApplyScaledRotation(
const Sophus::SE3f& T,
const float s,
const bool bScaledVel =
false);
98 void SetInertialSensor(
bool is_inertial);
100 void SetIniertialBA1();
101 void SetIniertialBA2();
102 bool GetIniertialBA1();
103 bool GetIniertialBA2();
104 void ChangeId(
uint04 nId);
108 LogPtr log() {
return m_log; }
109 Buffer<KeyFrame*> mvpKeyFrameOrigins;
110 KeyFrame* mpFirstRegionKF =
nullptr;
112 mutable std::mutex m_map_mutex;
113 std::mutex mMutexMapUpdate;
122 Set<uint04> msOptKFs;
123 Set<uint04> msFixedKFs;
128 Set<MapPoint*> m_map_points;
129 Set<KeyFrame*> mspKeyFrames;
130 KeyFrame* mpKFinitial =
nullptr;
131 KeyFrame* mpKFlowerID =
nullptr;
132 Buffer<MapPoint*> mvpReferenceMapPoints;
134 int mnMapChangeNotified = 0;
141 int mnBigChangeIdx = 0;
143 bool mbImuInitialized =
false;
144 bool mIsInUse =
false;
145 bool mHasTumbnail =
false;
148 bool mbIsInertial =
false;
149 bool mbIMU_BA1 =
false;
150 bool mbIMU_BA2 =
false;
Manages a collection of maps for the ORB-SLAM system.
The equivelent of std::vector but with a bit more control.
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.
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.
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.
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...