forked from raulmur/ORB_SLAM
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathMapPoint.h
136 lines (99 loc) · 3.16 KB
/
MapPoint.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
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
/**
* This file is part of ORB-SLAM.
*
* Copyright (C) 2014 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza)
* For more information see <http://webdiis.unizar.es/~raulmur/orbslam/>
*
* ORB-SLAM 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-SLAM 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-SLAM. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef MAPPOINT_H
#define MAPPOINT_H
#include<opencv2/core/core.hpp>
#include"KeyFrame.h"
#include"Map.h"
#include<boost/thread.hpp>
namespace ORB_SLAM
{
class ImageFeature;
class KeyFrame;
class Map;
class MapPoint
{
public:
MapPoint(const cv::Mat &Pos, KeyFrame* pRefKF, Map* pMap);
void SetWorldPos(const cv::Mat &Pos);
cv::Mat GetWorldPos();
cv::Mat GetNormal();
KeyFrame* GetReferenceKeyFrame();
std::map<KeyFrame*,size_t> GetObservations();
int Observations();
void AddObservation(KeyFrame* pKF,size_t idx);
void EraseObservation(KeyFrame* pKF);
int GetIndexInKeyFrame(KeyFrame* pKF);
bool IsInKeyFrame(KeyFrame* pKF);
void SetBadFlag();
bool isBad();
void Replace(MapPoint* pMP);
void IncreaseVisible();
void IncreaseFound();
float GetFoundRatio();
void ComputeDistinctiveDescriptors();
cv::Mat GetDescriptor();
void UpdateNormalAndDepth();
float GetMinDistanceInvariance();
float GetMaxDistanceInvariance();
public:
long unsigned int mnId;
static long unsigned int nNextId;
long int mnFirstKFid;
// Variables used by the tracking
float mTrackProjX;
float mTrackProjY;
bool mbTrackInView;
int mnTrackScaleLevel;
float mTrackViewCos;
long unsigned int mnTrackReferenceForFrame;
long unsigned int mnLastFrameSeen;
// Variables used by local mapping
long unsigned int mnBALocalForKF;
long unsigned int mnFuseCandidateForKF;
// Variables used by loop closing
long unsigned int mnLoopPointForKF;
long unsigned int mnCorrectedByKF;
long unsigned int mnCorrectedReference;
protected:
// Position in absolute coordinates
cv::Mat mWorldPos;
// Keyframes observing the point and associated index in keyframe
std::map<KeyFrame*,size_t> mObservations;
// Mean viewing direction
cv::Mat mNormalVector;
// Best descriptor to fast matching
cv::Mat mDescriptor;
// Reference KeyFrame
KeyFrame* mpRefKF;
// Tracking counters
int mnVisible;
int mnFound;
// Bad flag (we do not currently erase MapPoint from memory)
bool mbBad;
// Scale invariance distances
float mfMinDistance;
float mfMaxDistance;
Map* mpMap;
boost::mutex mMutexPos;
boost::mutex mMutexFeatures;
};
} //namespace ORB_SLAM
#endif // MAPPOINT_H