forked from jingpang/LearnVIORB
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Map.h
91 lines (67 loc) · 2.2 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
81
82
83
84
85
86
87
88
89
90
91
/**
* This file is part of ORB-SLAM2.
*
* Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <https://github.com/raulmur/ORB_SLAM2>
*
* ORB-SLAM2 is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM2 is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with ORB-SLAM2. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef MAP_H
#define MAP_H
#include "MapPoint.h"
#include "KeyFrame.h"
#include <set>
#include <mutex>
namespace ORB_SLAM2
{
class MapPoint;
class KeyFrame;
class KFIdComapre
{
public:
bool operator()(const KeyFrame* kfleft,const KeyFrame* kfright) const;
};
class Map
{
public:
// Update after an absolute scale is available
void UpdateScale(const double &scale);
//-----------------------------------------
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();
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*,KFIdComapre> mspKeyFrames;
std::vector<MapPoint*> mvpReferenceMapPoints;
long unsigned int mnMaxKFid;
std::mutex mMutexMap;
};
} //namespace ORB_SLAM
#endif // MAP_H