ORB-SLAM2源码学习:Tracking.cc:Tracking::TrackReferenceKeyFrame参考关键帧跟踪

发布于:2024-12-18 ⋅ 阅读:(49) ⋅ 点赞:(0)

前言

在 SLAM(同步定位与建图)中,跟踪线程是核心模块之一。它负责根据相机的传感器数据(如图像)估计相机的位姿(位置和朝向)。跟踪的准确性直接决定了整个系统的稳定性和精度。参考关键帧跟踪的基本思路是:使用一张已知位姿的关键帧(通常是地图中某个之前记录下来的关键帧)来跟踪当前普通帧(位姿未知)。通过匹配当前帧中的特征点和参考关键帧中的特征点,进而估计当前帧的位姿。

应用场景:

1. 地图刚刚初始化之后,此时恒速模型中的速度为空。这时只能使用参考关键帧,也就是初始化的第1 、2 帧对当前帧进行跟踪。

2. 恒速模型跟踪失败后,尝试用最近的参考关键帧跟踪当前普通帧。因为在恒速模型中估计的速度并不准确,可能会导致错误匹配,并且恒速模型只利用了前一帧的信息,信息量也有限,跟踪失败的可能性较大。而参考关键帧可能在局部建图线程中新匹配了更多的地图点并且参考关键帧的位姿是经过多次优化的,更准确。

1.函数声明 

bool Tracking::TrackReferenceKeyFrame()

2.函数定义 

步骤: 

1.将当前普通帧的描述子转化为词袋向量。

2.调用SearchByBoW函数通过词袋加快当前普通帧和参考关键帧之间的特征点匹配。 

3.将上一帧的位姿作为当前帧位姿的初始值(可以加速收敛),通过优化3D-2D 的重投影误差获得准确位姿。三维地图点来自匹配成功的参考帧, 二维特征点来自当前普通帧,BA 优化仅优化位姿,不优化地图点坐标(减少计算量)。

4. 剔除优化后的匹配点中的外点。

最终成功匹配的地图点数超过阈值,则认为成功跟踪。 

/*
 * @brief 用参考关键帧的地图点来对当前普通帧进行跟踪
 * 
 * Step 1:将当前普通帧的描述子转化为BoW向量
 * Step 2:通过词袋BoW加速当前帧与参考帧之间的特征点匹配
 * Step 3: 将上一帧的位姿态作为当前帧位姿的初始值
 * Step 4: 通过优化3D-2D的重投影误差来获得位姿
 * Step 5:剔除优化后的匹配点中的外点
 * @return 如果匹配数超10,返回true
 * 
 */
bool Tracking::TrackReferenceKeyFrame()
{
    // Compute Bag of Words vector
    // Step 1:将当前帧的描述子转化为BoW向量
    mCurrentFrame.ComputeBoW();

    // We perform first an ORB matching with the reference keyframe
    // If enough matches are found we setup a PnP solver
    ORBmatcher matcher(0.7,true);
    vector<MapPoint*> vpMapPointMatches;

    // Step 2:通过词袋BoW加速当前帧与参考帧之间的特征点匹配
    int nmatches = matcher.SearchByBoW(
        mpReferenceKF,          //参考关键帧
        mCurrentFrame,          //当前帧
        vpMapPointMatches);     //存储匹配关系

    // 匹配数目小于15,认为跟踪失败
    if(nmatches<15)
        return false;

    // Step 3:将上一帧的位姿态作为当前帧位姿的初始值
    mCurrentFrame.mvpMapPoints = vpMapPointMatches;
    mCurrentFrame.SetPose(mLastFrame.mTcw); // 用上一次的Tcw设置初值,在PoseOptimization可以收敛快一些

    // Step 4:通过优化3D-2D的重投影误差来获得位姿
    Optimizer::PoseOptimization(&mCurrentFrame);

    // Discard outliers
    // Step 5:剔除优化后的匹配点中的外点
    //之所以在优化之后才剔除外点,是因为在优化的过程中就有了对这些外点的标记
    int nmatchesMap = 0;
    for(int i =0; i<mCurrentFrame.N; i++)
    {
        if(mCurrentFrame.mvpMapPoints[i])
        {
            //如果对应到的某个特征点是外点
            if(mCurrentFrame.mvbOutlier[i])
            {
                //清除它在当前帧中存在过的痕迹
                MapPoint* pMP = mCurrentFrame.mvpMapPoints[i];

                mCurrentFrame.mvpMapPoints[i]=static_cast<MapPoint*>(NULL);
                mCurrentFrame.mvbOutlier[i]=false;
                pMP->mbTrackInView = false;
                pMP->mnLastFrameSeen = mCurrentFrame.mnId;
                nmatches--;
            }
            else if(mCurrentFrame.mvpMapPoints[i]->Observations()>0)
                //匹配的内点计数++
                nmatchesMap++;
        }
    }
    // 跟踪成功的数目超过10才认为跟踪成功,否则跟踪失败
    return nmatchesMap>=10;
}

结束语

以上就是我学习到的内容,如果对您有帮助请多多支持我,如果哪里有问题欢迎大家在评论区积极讨论,我看到会及时回复。


网站公告

今日签到

点亮在社区的每一天
去签到