ORB SLA2
Map.h
1 
21 #ifndef MAP_H
22 #define MAP_H
23 
24 #include "MapPoint.h"
25 #include "KeyFrame.h"
26 #include <set>
27 
28 #include <mutex>
29 
30 
31 
32 namespace ORB_SLAM2
33 {
34 
35 class MapPoint;
36 class KeyFrame;
37 
38 class Map
39 {
40 public:
41  Map();
42 
43  void AddKeyFrame(KeyFrame* pKF);
44  void AddMapPoint(MapPoint* pMP);
45  void EraseMapPoint(MapPoint* pMP);
46  void EraseKeyFrame(KeyFrame* pKF);
47  void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
48  void InformNewBigChange();
49  int GetLastBigChangeIdx();
50 
51  std::vector<KeyFrame*> GetAllKeyFrames();
52  std::vector<MapPoint*> GetAllMapPoints();
53  std::vector<MapPoint*> GetReferenceMapPoints();
54 
55  long unsigned int MapPointsInMap();
56  long unsigned KeyFramesInMap();
57 
58  long unsigned int GetMaxKFid();
59 
60  void clear();
61 
62  vector<KeyFrame*> mvpKeyFrameOrigins;
63 
64  std::mutex mMutexMapUpdate;
65 
66  // This avoid that two points are created simultaneously in separate threads (id conflict)
67  std::mutex mMutexPointCreation;
68 
69 protected:
70  std::set<MapPoint*> mspMapPoints;
71  std::set<KeyFrame*> mspKeyFrames;
72 
73  std::vector<MapPoint*> mvpReferenceMapPoints;
74 
75  long unsigned int mnMaxKFid;
76 
77  // Index related to a big change in the map (loop closure, global BA)
78  int mnBigChangeIdx;
79 
80  std::mutex mMutexMap;
81 };
82 
83 } //namespace ORB_SLAM
84 
85 #endif // MAP_H
Definition: KeyFrame.h:43
Definition: Converter.cpp:24
Definition: MapPoint.h:39
Definition: Map.h:38