-
Notifications
You must be signed in to change notification settings - Fork 3.1k
Expand file tree
/
Copy pathMapPoint.h
More file actions
256 lines (198 loc) · 7.07 KB
/
MapPoint.h
File metadata and controls
256 lines (198 loc) · 7.07 KB
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
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 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-SLAM3 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-SLAM3.
* If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef MAPPOINT_H
#define MAPPOINT_H
#include "KeyFrame.h"
#include "Frame.h"
#include "Map.h"
#include "Converter.h"
#include "SerializationUtils.h"
#include <opencv2/core/core.hpp>
#include <mutex>
#include <boost/serialization/serialization.hpp>
#include <boost/serialization/array.hpp>
#include <boost/serialization/map.hpp>
namespace ORB_SLAM3
{
class KeyFrame;
class Map;
class Frame;
class MapPoint
{
friend class boost::serialization::access;
template<class Archive>
void serialize(Archive & ar, const unsigned int version)
{
ar & mnId;
ar & mnFirstKFid;
ar & mnFirstFrame;
ar & nObs;
// Variables used by the tracking
//ar & mTrackProjX;
//ar & mTrackProjY;
//ar & mTrackDepth;
//ar & mTrackDepthR;
//ar & mTrackProjXR;
//ar & mTrackProjYR;
//ar & mbTrackInView;
//ar & mbTrackInViewR;
//ar & mnTrackScaleLevel;
//ar & mnTrackScaleLevelR;
//ar & mTrackViewCos;
//ar & mTrackViewCosR;
//ar & mnTrackReferenceForFrame;
//ar & mnLastFrameSeen;
// Variables used by local mapping
//ar & mnBALocalForKF;
//ar & mnFuseCandidateForKF;
// Variables used by loop closing and merging
//ar & mnLoopPointForKF;
//ar & mnCorrectedByKF;
//ar & mnCorrectedReference;
//serializeMatrix(ar,mPosGBA,version);
//ar & mnBAGlobalForKF;
//ar & mnBALocalForMerge;
//serializeMatrix(ar,mPosMerge,version);
//serializeMatrix(ar,mNormalVectorMerge,version);
// Protected variables
ar & boost::serialization::make_array(mWorldPos.data(), mWorldPos.size());
ar & boost::serialization::make_array(mNormalVector.data(), mNormalVector.size());
//ar & BOOST_SERIALIZATION_NVP(mBackupObservationsId);
//ar & mObservations;
ar & mBackupObservationsId1;
ar & mBackupObservationsId2;
serializeMatrix(ar,mDescriptor,version);
ar & mBackupRefKFId;
//ar & mnVisible;
//ar & mnFound;
ar & mbBad;
ar & mBackupReplacedId;
ar & mfMinDistance;
ar & mfMaxDistance;
}
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
MapPoint();
MapPoint(const Eigen::Vector3f &Pos, KeyFrame* pRefKF, Map* pMap);
MapPoint(const double invDepth, cv::Point2f uv_init, KeyFrame* pRefKF, KeyFrame* pHostKF, Map* pMap);
MapPoint(const Eigen::Vector3f &Pos, Map* pMap, Frame* pFrame, const int &idxF);
void SetWorldPos(const Eigen::Vector3f &Pos);
Eigen::Vector3f GetWorldPos();
Eigen::Vector3f GetNormal();
void SetNormalVector(const Eigen::Vector3f& normal);
KeyFrame* GetReferenceKeyFrame();
std::map<KeyFrame*,std::tuple<int,int>> GetObservations();
int Observations();
void AddObservation(KeyFrame* pKF,int idx);
void EraseObservation(KeyFrame* pKF);
std::tuple<int,int> GetIndexInKeyFrame(KeyFrame* pKF);
bool IsInKeyFrame(KeyFrame* pKF);
void SetBadFlag();
bool isBad();
void Replace(MapPoint* pMP);
MapPoint* GetReplaced();
void IncreaseVisible(int n=1);
void IncreaseFound(int n=1);
float GetFoundRatio();
inline int GetFound(){
return mnFound;
}
void ComputeDistinctiveDescriptors();
cv::Mat GetDescriptor();
void UpdateNormalAndDepth();
float GetMinDistanceInvariance();
float GetMaxDistanceInvariance();
int PredictScale(const float ¤tDist, KeyFrame*pKF);
int PredictScale(const float ¤tDist, Frame* pF);
Map* GetMap();
void UpdateMap(Map* pMap);
void PrintObservations();
void PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP);
void PostLoad(map<long unsigned int, KeyFrame*>& mpKFid, map<long unsigned int, MapPoint*>& mpMPid);
public:
long unsigned int mnId;
static long unsigned int nNextId;
long int mnFirstKFid;
long int mnFirstFrame;
int nObs;
// Variables used by the tracking
float mTrackProjX;
float mTrackProjY;
float mTrackDepth;
float mTrackDepthR;
float mTrackProjXR;
float mTrackProjYR;
bool mbTrackInView, mbTrackInViewR;
int mnTrackScaleLevel, mnTrackScaleLevelR;
float mTrackViewCos, mTrackViewCosR;
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;
Eigen::Vector3f mPosGBA;
long unsigned int mnBAGlobalForKF;
long unsigned int mnBALocalForMerge;
// Variable used by merging
Eigen::Vector3f mPosMerge;
Eigen::Vector3f mNormalVectorMerge;
// Fopr inverse depth optimization
double mInvDepth;
double mInitU;
double mInitV;
KeyFrame* mpHostKF;
static std::mutex mGlobalMutex;
unsigned int mnOriginMapId;
protected:
// Position in absolute coordinates
Eigen::Vector3f mWorldPos;
// Keyframes observing the point and associated index in keyframe
std::map<KeyFrame*,std::tuple<int,int> > mObservations;
// For save relation without pointer, this is necessary for save/load function
std::map<long unsigned int, int> mBackupObservationsId1;
std::map<long unsigned int, int> mBackupObservationsId2;
// Mean viewing direction
Eigen::Vector3f mNormalVector;
// Best descriptor to fast matching
cv::Mat mDescriptor;
// Reference KeyFrame
KeyFrame* mpRefKF;
long unsigned int mBackupRefKFId;
// Tracking counters
int mnVisible;
int mnFound;
// Bad flag (we do not currently erase MapPoint from memory)
bool mbBad;
MapPoint* mpReplaced;
// For save relation without pointer, this is necessary for save/load function
long long int mBackupReplacedId;
// Scale invariance distances
float mfMinDistance;
float mfMaxDistance;
Map* mpMap;
// Mutex
std::mutex mMutexPos;
std::mutex mMutexFeatures;
std::mutex mMutexMap;
};
} //namespace ORB_SLAM
#endif // MAPPOINT_H