forked from Ewenwan/ORB-SLAM-RGBD-with-Octomap
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathMap.h
80 lines (55 loc) · 1.84 KB
/
Map.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
/**
* This file is part of ORB-SLAM2.
* 地图管理器-添加地图保存、载入函数===
*/
#ifndef MAP_H
#define MAP_H
#include "MapPoint.h"
#include "KeyFrame.h"
#include <set>
#include <mutex>
namespace ORB_SLAM2
{
class MapPoint;
class KeyFrame;
// ============= 读取地图 还原关键帧时需要用到=====
class ORBextractor;
class Map
{
public:
Map();
void AddKeyFrame(KeyFrame* pKF);
void AddMapPoint(MapPoint* pMP);
void EraseMapPoint(MapPoint* pMP);
void EraseKeyFrame(KeyFrame* pKF);
void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
std::vector<KeyFrame*> GetAllKeyFrames();
std::vector<MapPoint*> GetAllMapPoints();
std::vector<MapPoint*> GetReferenceMapPoints();
long unsigned int MapPointsInMap();
long unsigned KeyFramesInMap();
long unsigned int GetMaxKFid();
void clear();
// ===============new====================
bool Save(const string &filename);
bool Load(const string &filename, ORBVocabulary &voc);
// ======================================
vector<KeyFrame*> mvpKeyFrameOrigins;
std::mutex mMutexMapUpdate;
// This avoid that two points are created simultaneously in separate threads (id conflict)
std::mutex mMutexPointCreation;
protected:
std::set<MapPoint*> mspMapPoints;
std::set<KeyFrame*> mspKeyFrames;
std::vector<MapPoint*> mvpReferenceMapPoints;
long unsigned int mnMaxKFid;
std::mutex mMutexMap;
// ====================new==============================
void _WriteMapPoint(ofstream &f, MapPoint* mp);
void _WriteKeyFrame(ofstream &f, KeyFrame* kf, map<MapPoint*, unsigned long int>& idx_of_mp);
MapPoint* _ReadMapPoint(ifstream &f);
KeyFrame* _ReadKeyFrame(ifstream &f, ORBVocabulary &voc, std::vector<MapPoint*> amp, ORBextractor* ex);
//=====================
};
} //namespace ORB_SLAM2
#endif // MAP_H