Map.h
Go to the documentation of this file.
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 using namespace std;
31 
32 namespace ORB_SLAM2
33 {
34 
35 class MapPoint;
36 class KeyFrame;
37 
38 class Map
39 {
40 public:
41  Map();
42 
43  bool SaveWithTimestamps(const string &filename);
44  bool SaveWithPose(const string &filename);
45 
46  void _WriteMapPoint(ofstream &f, MapPoint* mp,
47  const std::string &end_marker = "\n");
48  void _WriteMapPointObj(ofstream &f, MapPoint* mp,
49  const std::string &end_marker="\n");
50 
51  void AddKeyFrame(KeyFrame* pKF);
52  void AddMapPoint(MapPoint* pMP);
53  void EraseMapPoint(MapPoint* pMP);
54  void EraseKeyFrame(KeyFrame* pKF);
55  void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
56  void InformNewBigChange();
57  int GetLastBigChangeIdx();
58 
59  std::vector<KeyFrame*> GetAllKeyFrames();
60  std::vector<MapPoint*> GetAllMapPoints();
61  std::vector<MapPoint*> GetReferenceMapPoints();
62 
63  long unsigned int MapPointsInMap();
64  long unsigned KeyFramesInMap();
65 
66  long unsigned int GetMaxKFid();
67 
68  void clear();
69 
70  vector<KeyFrame*> mvpKeyFrameOrigins;
71 
72  std::mutex mMutexMapUpdate;
73 
74  // This avoid that two points are created simultaneously in separate threads (id conflict)
75  std::mutex mMutexPointCreation;
76 
77 protected:
78  std::set<MapPoint*> mspMapPoints;
79  std::set<KeyFrame*> mspKeyFrames;
80 
81  std::vector<MapPoint*> mvpReferenceMapPoints;
82 
83  long unsigned int mnMaxKFid;
84 
85  // Index related to a big change in the map (loop closure, global BA)
87 
88  std::mutex mMutexMap;
89  void GetMapPointsIdx();
90 };
91 
92 } //namespace ORB_SLAM
93 
94 #endif // MAP_H
filename
std::mutex mMutexPointCreation
Definition: Map.h:75
std::mutex mMutexMap
Definition: Map.h:88
f
std::vector< MapPoint * > mvpReferenceMapPoints
Definition: Map.h:81
std::mutex mMutexMapUpdate
Definition: Map.h:72
long unsigned int mnMaxKFid
Definition: Map.h:83
vector< KeyFrame * > mvpKeyFrameOrigins
Definition: Map.h:70
int mnBigChangeIdx
Definition: Map.h:86
std::set< MapPoint * > mspMapPoints
Definition: Map.h:78
std::set< KeyFrame * > mspKeyFrames
Definition: Map.h:79


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47