ORB-SLAM2的前端VO部分分为:Tracking和LocalMapping,
Tracking线程负责根据输入的Frame恢复出相机位姿T并跟踪局部地图,最后生成关键帧传给LocalMapping线程。
LocalMapping线程负责对新加入的KeyFrames和MapPoints筛选融合,剔除冗余的KeyFrames和MapPoints,维护稳定的KeyFrame集合,传给后续的LoopClosing线程。
LocalMapping主要流程
主要的功能点在:
- 处理新的关键帧ProcessNewKeyFrame()
- 剔除不合格地图点MapPointCulling()
- 三角化恢复新地图点CreateNewMapPoints()
- 融合当前帧与相邻帧重复的地图点SearchInNeighbors()
- 局部BA优化LocalBundleAdjustment()
- 剔除冗余关键帧KeyFrameCulling()
LocalMapping整体流程
1、SetAcceptKeyFrames(false)
告诉Tracking线程,LocalMapping正处于繁忙状态,不要再添加新的关键帧了。
2、ProcessNewKeyFrame()
计算关键帧BoW向量,将关键帧插入地图,更新Covisibility图和Essential图
(1)从缓冲队列中取出一帧关键帧
// Tracking线程向LocalMapping中插入关键帧存在该队列中
{
unique_lock<mutex> lock(mMutexNewKFs);
// 从列表最前面中获得一个等待被插入的关键帧,原列表少一个关键帧
mpCurrentKeyFrame = mlNewKeyFrames.front();
mlNewKeyFrames.pop_front();
}
(2)计算当前关键帧的Bow向量,有助于加速三角化新的MapPoints
mpCurrentKeyFrame->ComputeBoW();
(3)更新当前关键帧所看到的地图点的属性(平均观测方向,最优描述子)
const vector<MapPoint*> vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
for(size_t i=0; i<vpMapPointMatches.size(); i++)
{
MapPoint* pMP = vpMapPointMatches[i];
if(pMP)
{
if(!pMP->isBad())
{
// 非当前帧生成的MapPoints
// 为当前帧在tracking过程跟踪到的MapPoints更新属性
if(!pMP->IsInKeyFrame(mpCurrentKeyFrame))
{
// 添加观测
pMP->AddObservation(mpCurrentKeyFrame, i);
// 获得该点的平均观测方向和观测距离范围
pMP->UpdateNormalAndDepth();
// 加入关键帧后,更新3d点的最佳描述子
pMP->ComputeDistinctiveDescriptors();
}
else // th