forked from Ewenwan/ORB_SLAM2_SSD_Semantic
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathKeyFrame.h
252 lines (202 loc) · 8.01 KB
/
KeyFrame.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
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
/**
* This file is part of ORB-SLAM2.
* 关键帧
*
* 普通帧里面精选出来的具有代表性的帧
*
*
*/
#ifndef KEYFRAME_H
#define KEYFRAME_H
#include "MapPoint.h"
#include "Thirdparty/DBoW2/DBoW2/BowVector.h"
#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
#include "ORBVocabulary.h"
#include "ORBextractor.h"
#include "Frame.h"
#include "KeyFrameDatabase.h"
#include <mutex>
namespace ORB_SLAM2
{
class Map;// 地图
class MapPoint;// 地图点
class Frame;// 普通帧
class KeyFrameDatabase;//关键帧数据库 存储关键点 位姿态等信息 用于匹配
class KeyFrame
{
public:
// 初始化关键帧
// 普通帧的 量全部复制过来
KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB);
// Pose functions
void SetPose(const cv::Mat &Tcw);
cv::Mat GetPose();// 位姿
cv::Mat GetPoseInverse();// 位姿
cv::Mat GetCameraCenter();// 单目 相机中心
cv::Mat GetStereoCenter();// 双目 相机中心
cv::Mat GetRotation();// 旋转矩阵
cv::Mat GetTranslation();// 平移向量
// Bag of Words Representation
// 计关键点 描述子 的 词典线性表示向量
void ComputeBoW();
// Covisibility graph functions
// 可视化 添加 线连接 关键点连线
void AddConnection(KeyFrame* pKF, const int &weight);
void EraseConnection(KeyFrame* pKF);// 删除 线连接
void UpdateConnections();// 跟新线连接
void UpdateBestCovisibles();
std::set<KeyFrame *> GetConnectedKeyFrames();
std::vector<KeyFrame* > GetVectorCovisibleKeyFrames();
std::vector<KeyFrame*> GetBestCovisibilityKeyFrames(const int &N);
std::vector<KeyFrame*> GetCovisiblesByWeight(const int &w);
int GetWeight(KeyFrame* pKF);
// Spanning tree functions 生成 关键帧 树
void AddChild(KeyFrame* pKF);// 添加孩子
void EraseChild(KeyFrame* pKF);// 删除孩子
void ChangeParent(KeyFrame* pKF);// 跟换父亲
std::set<KeyFrame*> GetChilds();// 得到孩子
KeyFrame* GetParent();//得到父亲
bool hasChild(KeyFrame* pKF);// 有孩子吗
// Loop Edges 环边
void AddLoopEdge(KeyFrame* pKF);// 添加
std::set<KeyFrame*> GetLoopEdges();// 获取
// MapPoint observation functions
// 地图点 观测函数
void AddMapPoint(MapPoint* pMP, const size_t &idx);// 添加 地图点
void EraseMapPointMatch(const size_t &idx);// 删除地图点匹配
void EraseMapPointMatch(MapPoint* pMP);
void ReplaceMapPointMatch(const size_t &idx, MapPoint* pMP);// 替换地图点匹配
std::set<MapPoint*> GetMapPoints();// 得到地图点集合 set 指针
std::vector<MapPoint*> GetMapPointMatches();// 得到地图点匹配
int TrackedMapPoints(const int &minObs);// 跟踪到的地图点
MapPoint* GetMapPoint(const size_t &idx);//得到单个地图点
// KeyPoint functions
// 关键点 方程
std::vector<size_t> GetFeaturesInArea(const float &x, const float &y, const float &r) const;
cv::Mat UnprojectStereo(int i);
// Image
// 在图像里吗
bool IsInImage(const float &x, const float &y) const;
// Enable/Disable bad flag changes
// 使能/关能
void SetNotErase();
void SetErase();
// Set/check bad flag
// 设置标志 检查标志
void SetBadFlag();
bool isBad();
// Compute Scene Depth (q=2 median). Used in monocular.
// 单目 环境 深度中值
float ComputeSceneMedianDepth(const int q);
// 比较函数
static bool weightComp( int a, int b){
return a>b;
}
// 关键帧 先后顺序
static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){
return pKF1->mnId<pKF2->mnId;
}
// The following variables are accesed from only 1 thread or never change (no mutex needed).
// 变量
public:
static long unsigned int nNextId;// 下一个关键帧 id
long unsigned int mnId;// 本关键帧 id
const long unsigned int mnFrameId;// 帧id
const double mTimeStamp;// 时间戳
// Grid (to speed up feature matching)
// 640 *480 图像 分成 64 × 48 个格子 加速 特征匹配
const int mnGridCols;// 64 列
const int mnGridRows;// 48 行
const float mfGridElementWidthInv;// 每一像素 占有的 格子数量
const float mfGridElementHeightInv;
// Variables used by the tracking
long unsigned int mnTrackReferenceForFrame;// 参考帧
long unsigned int mnFuseTargetForKF;// 做过相邻匹配 标志 在 LocalMapping::SearchInNeighbors() 使用
// Variables used by the local mapping
// 本地地图 最小化重投影误差 BA参数
long unsigned int mnBALocalForKF;
long unsigned int mnBAFixedForKF;
// Variables used by the keyframe database
// 关键帧数据库 变量参数
long unsigned int mnLoopQuery;
int mnLoopWords;
float mLoopScore;
long unsigned int mnRelocQuery;
int mnRelocWords;
float mRelocScore;
// Variables used by loop closing
// 闭环检测 变量
cv::Mat mTcwGBA;
cv::Mat mTcwBefGBA;
long unsigned int mnBAGlobalForKF;
// Calibration parameters
// 校准参数 相机内参 基线*焦距 基线 深度
const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth;
// Number of KeyPoints
// 关键点数量
const int N;//
// KeyPoints, stereo coordinate and descriptors (all associated by an index)
// 关键点 校正后的关键点 匹配点横坐标 深度值 描述子
const std::vector<cv::KeyPoint> mvKeys;// 关键点
const std::vector<cv::KeyPoint> mvKeysUn;// 校正后的关键点
const std::vector<float> mvuRight; // negative value for monocular points 匹配点横坐标
const std::vector<float> mvDepth; // negative value for monocular points
const cv::Mat mDescriptors;// 描述子
//BoW
// 词带模型
DBoW2::BowVector mBowVec; // 描述子 词典单词 线性表示 的向量
DBoW2::FeatureVector mFeatVec;// feature vector of nodes and feature indexes
// Pose relative to parent (this is computed when bad flag is activated)
cv::Mat mTcp;// 父位姿 到 当前关键帧 转换矩阵
// Scale 图像金字塔尺度信息
const int mnScaleLevels;
const float mfScaleFactor;
const float mfLogScaleFactor;
const std::vector<float> mvScaleFactors;
const std::vector<float> mvLevelSigma2;
const std::vector<float> mvInvLevelSigma2;// g2o 优化时 对于边(误差) 的权重
// Image bounds and calibration
// 图像四个顶点 畸变校正后 得到 的图像 尺寸
const int mnMinX;
const int mnMinY;
const int mnMaxX;
const int mnMaxY;
const cv::Mat mK;
// The following variables need to be accessed trough a mutex to be thread safe.
protected:
// SE3 Pose and camera center
cv::Mat Tcw;// 世界 到 相机
cv::Mat Twc;// 相机 到 世界
cv::Mat Ow;// 相机坐标
cv::Mat Cw; // 双目相机中心点(基线中心)坐标 Stereo middel point. Only for visualization
// MapPoints associated to keypoints
// 地图点
std::vector<MapPoint*> mvpMapPoints;
// BoW
// 关键帧数据库 特征字典
KeyFrameDatabase* mpKeyFrameDB;
ORBVocabulary* mpORBvocabulary;
// Grid over the image to speed up feature matching
// 格点 64*48个容器 每个容器内是一个容器 存储着 关键点 的 id
std::vector< std::vector <std::vector<size_t> > > mGrid;
std::map<KeyFrame*,int> mConnectedKeyFrameWeights;// 帧 和 权重 key :value 数对
std::vector<KeyFrame*> mvpOrderedConnectedKeyFrames;
std::vector<int> mvOrderedWeights;
// Spanning Tree and Loop Edges
// 生成树
bool mbFirstConnection;
KeyFrame* mpParent;//父节点
std::set<KeyFrame*> mspChildrens;//子节点
std::set<KeyFrame*> mspLoopEdges;//环边
// Bad flags
bool mbNotErase;
bool mbToBeErased;
bool mbBad;
float mHalfBaseline; // Only for visualization 基线的一半 用于显示
Map* mpMap;
std::mutex mMutexPose;
std::mutex mMutexConnections;
std::mutex mMutexFeatures;
};
} //namespace ORB_SLAM
#endif // KEYFRAME_H