ORB-SLAM2算法14之局部建图线程Local Mapping

news2024/11/26 20:27:06

文章目录

  • 0 引言
  • 1 概述
  • 2 处理队列中的关键帧
  • 3 剔除坏的地图点
  • 4 创建新地图点
  • 5 融合当前关键帧和其共视帧的地图点
  • 6 局部BA优化
  • 7 剔除冗余关键帧

0 引言

ORB-SLAM2算法7详细了解了System主类和多线程、ORB-SLAM2学习笔记8详细了解了图像特征点提取和描述子的生成、ORB-SLAM2算法9详细了解了图像帧、ORB-SLAM2算法10详细了解了图像关键帧、ORB-SLAM2算法11详细了解了地图点及ORB-SLAM2算法12详细了解了单目初始化,ORB-SLAM2算法13详细了解了ORB-SLAM2中的三大线程中的跟踪线程Tracking。本文主要学习ORB-SLAM2中的三大线程中的局部建图线程Local Mapping

请添加图片描述

1 概述

ORB-SLAM2算法中,局部建图Local Mapping作为一个单独的线程,从系统启动后就开始运行,只是在上一篇Tracking线程生成新的关键帧,并插入到Local Mapping线程中的成员变量mlNewKeyFrames列表后,Local Mapping线程检测到该列表中有关键帧后才开始处理这些新插入的关键帧,如果没有关键帧插入的时候,Local Mapping线程是处于空闲的睡眠状态

Local Mapping线程的主要流程:

  1. 首先请求停止建图,如果不停止继续下一步;
  2. 告诉Tracking线程,Local Mapping线程正处于繁忙状态,暂停接收关键帧SetAcceptKeyFrames(false)
  3. 处理列表中的关键帧,包括计算BOW、更新观测、描述子、共视图,插入到地图等;
  4. 根据地图点的观测情况剔除质量不好的地图点;
  5. 当前关键帧与相邻关键帧通过三角化产生新的地图点,使得跟踪更稳定;
  6. 如果已经处理完最后的一个关键帧,检查并融合当前关键帧与相邻关键帧帧(两级相邻)中重复的地图点;
  7. 如果已经处理完最后一个关键帧,且闭环检测线程没有请求停止建图,当局部地图中的关键帧大于2个的时候进行局部地图的BA,并检测并剔除当前帧相邻的关键帧中冗余的关键帧;
  8. 设置继续接收当前帧SetAcceptKeyFrames(true),并暂停当前线程3秒,然后回归第1步。

主要流程图如下:

请添加图片描述

// 线程主函数

void LocalMapping::Run()
{

    // 标记状态,表示当前run函数正在运行,尚未结束
    mbFinished = false;
    // 主循环
    while(1)
    {
        // Tracking will see that Local Mapping is busy
        // Step 1 告诉Tracking,LocalMapping正处于繁忙状态,请不要给我发送关键帧打扰我
        // LocalMapping线程处理的关键帧都是Tracking线程发来的
        SetAcceptKeyFrames(false);

        // Check if there are keyframes in the queue
        // 等待处理的关键帧列表不为空
        if(CheckNewKeyFrames())
        {
            // BoW conversion and insertion in Map
            // Step 2 处理列表中的关键帧,包括计算BoW、更新观测、描述子、共视图,插入到地图等
            ProcessNewKeyFrame();

            // Check recent MapPoints
            // Step 3 根据地图点的观测情况剔除质量不好的地图点
            MapPointCulling();

            // Triangulate new MapPoints
            // Step 4 当前关键帧与相邻关键帧通过三角化产生新的地图点,使得跟踪更稳
            CreateNewMapPoints();

            // 已经处理完队列中的最后的一个关键帧
            if(!CheckNewKeyFrames())
            {
                // Find more matches in neighbor keyframes and fuse point duplications
                //  Step 5 检查并融合当前关键帧与相邻关键帧帧(两级相邻)中重复的地图点
                SearchInNeighbors();
            }

            // 终止BA的标志
            mbAbortBA = false;

            // 已经处理完队列中的最后的一个关键帧,并且闭环检测没有请求停止LocalMapping
            if(!CheckNewKeyFrames() && !stopRequested())
            {
                // Local BA
                // Step 6 当局部地图中的关键帧大于2个的时候进行局部地图的BA
                if(mpMap->KeyFramesInMap()>2)
                    // 注意这里的第二个参数是按地址传递的,当这里的 mbAbortBA 状态发生变化时,能够及时执行/停止BA
                    Optimizer::LocalBundleAdjustment(mpCurrentKeyFrame,&mbAbortBA, mpMap);

                // Check redundant local Keyframes
                // Step 7 检测并剔除当前帧相邻的关键帧中冗余的关键帧
                // 冗余的判定:该关键帧的90%的地图点可以被其它关键帧观测到
                KeyFrameCulling();
            }

            // Step 8 将当前帧加入到闭环检测队列中
            // 注意这里的关键帧被设置成为了bad的情况,这个需要注意
            mpLoopCloser->InsertKeyFrame(mpCurrentKeyFrame);
        }
        else if(Stop())     // 当要终止当前线程的时候
        {
            // Safe area to stop
            while(isStopped() && !CheckFinish())
            {
                // 如果还没有结束利索,那么等
                // usleep(3000);
                std::this_thread::sleep_for(std::chrono::milliseconds(3));
            }
            // 然后确定终止了就跳出这个线程的主循环
            if(CheckFinish())
                break;
        }

        // 查看是否有复位线程的请求
        ResetIfRequested();

        // Tracking will see that Local Mapping is not busy
        SetAcceptKeyFrames(true);

        // 如果当前线程已经结束了就跳出主循环
        if(CheckFinish())
            break;

        //usleep(3000);
        std::this_thread::sleep_for(std::chrono::milliseconds(3));

    }

    // 设置线程已经终止
    SetFinish();
}

以下是针对上述流程中的主要步骤详细阐述,比如如何处理队列中的关键帧、剔除坏的地图点及局部BA优化等等。

2 处理队列中的关键帧

该步骤主要是通过成员函数void LocalMapping::ProcessNewKeyFrame()实现的,包括计算词袋BOW、更新观测、描述子、共视图及插入到地图等。主要实现步骤如下:

  1. 从缓冲队列中取出一帧关键帧mpCurrentKeyFrame
  2. 计算该关键帧mpCurrentKeyFrame的词袋向量;
  3. 处理关键帧的地图点:更新地图点平均观测方向、更新该点的平均观测方向和观测距离范围、更新地图点的最佳描述子;
  4. 更新关键帧间的连接关系(共视图),主要更新下列变量:
    • mConnectedKeyFrameWeights:当前关键帧的共视信息,记录当前关键帧共视关键帧的信息
    • mvpOrderedConnectedKeyFrames:对mConnectedKeyFrameWeights中超过共视阈值的关键帧
    • mvOrderedWeights:对mConnectedKeyFrameWeights中超过共视阈值的关键帧的共视程度
    • mpParent:共视程度最高的那个关键帧
    • mspChildrens:建立双向关系,将当前帧的共视程度最高的那个关键帧的子关键帧添加当前帧
  5. 将该关键帧mpCurrentKeyFrame插入地图。
// 处理列表中的关键帧,包括计算BoW、更新观测、描述子、共视图,插入到地图等

void LocalMapping::ProcessNewKeyFrame()
{
    // Step 1:从缓冲队列中取出一帧关键帧
    // 该关键帧队列是Tracking线程向LocalMapping中插入的关键帧组成
    {
        unique_lock<mutex> lock(mMutexNewKFs);
        // 取出列表中最前面的关键帧,作为当前要处理的关键帧
        mpCurrentKeyFrame = mlNewKeyFrames.front();
        // 取出最前面的关键帧后,在原来的列表里删掉该关键帧
        mlNewKeyFrames.pop_front();
    }

    // Compute Bags of Words structures
    // Step 2:计算该关键帧特征点的词袋向量
    mpCurrentKeyFrame->ComputeBoW();

    // Associate MapPoints to the new keyframe and update normal and descriptor
    // Step 3:当前处理关键帧中有效的地图点,更新normal,描述子等信息
    // TrackLocalMap中和当前帧新匹配上的地图点和当前关键帧进行关联绑定
    const vector<MapPoint*> vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
    // 对当前处理的这个关键帧中的所有的地图点展开遍历
    for(size_t i=0; i<vpMapPointMatches.size(); i++)
    {
        MapPoint* pMP = vpMapPointMatches[i];
        if(pMP)
        {
            if(!pMP->isBad())
            {
                if(!pMP->IsInKeyFrame(mpCurrentKeyFrame))
                {
                    // 如果地图点不是来自当前帧的观测(比如来自局部地图点),为当前地图点添加观测
                    pMP->AddObservation(mpCurrentKeyFrame, i);
                    // 获得该点的平均观测方向和观测距离范围
                    pMP->UpdateNormalAndDepth();
                    // 更新地图点的最佳描述子
                    pMP->ComputeDistinctiveDescriptors();
                }
                else // this can only happen for new stereo points inserted by the Tracking
                {
                    // 这些地图点可能来自双目或RGBD在创建关键帧中新生成的地图点,或者是CreateNewMapPoints 中通过三角化产生
                    // 将上述地图点放入mlpRecentAddedMapPoints,等待后续MapPointCulling函数的检验
                    mlpRecentAddedMapPoints.push_back(pMP); 
                }
            }
        }
    }    

    // Update links in the Covisibility Graph
    // Step 4:更新关键帧间的连接关系(共视图)
    mpCurrentKeyFrame->UpdateConnections();

    // Insert Keyframe in Map
    // Step 5:将该关键帧插入到地图中
    mpMap->AddKeyFrame(mpCurrentKeyFrame);
}

3 剔除坏的地图点

该步骤主要通过成员函数void LocalMapping::MapPointCulling()实现的,主要实现步骤如下:

  1. 根据相机类型设置不同的观测阈值cnThObs单目设置为2双目/RGBD设置成3
  2. 遍历检查新添加的地图点;
    2.1 已经是坏的地图点,直接从队列中删除;
    2.2 跟踪到该地图点的帧数相比预计可观测到该地图点的帧数的比例小于25%,从地图中删除;
    2.3 从该点建立开始,到现在已经过了不小于2个关键帧,并且观测到该点的相机数却不超过阈值cnThObs,从地图中删除;
    2.4 从建立该点开始,已经过了3个关键帧而没有被剔除,则认为是质量高的点。

其中2.22.3中可知质量不好的地图点的判断标准:

  1. 召回率 = m n F o u n d m n V i s i b l e < 0.25 =\frac{mnFound}{mnVisible}<0.25 =mnVisiblemnFound<0.25
  2. 创建的3帧内观测数目少于设定阈值cnThObs

而质量好的地图点的判断标准就是:

  1. 连续3个关键帧仍未被剔除。
// 检查新增地图点,根据地图点的观测情况剔除质量不好的新增的地图点

void LocalMapping::MapPointCulling()
{
    // Check Recent Added MapPoints
    list<MapPoint*>::iterator lit = mlpRecentAddedMapPoints.begin();
    const unsigned long int nCurrentKFid = mpCurrentKeyFrame->mnId;

    // Step 1:根据相机类型设置不同的观测阈值
    int nThObs;
    if(mbMonocular)
        nThObs = 2;
    else
        nThObs = 3;
    const int cnThObs = nThObs;
	
	// Step 2:遍历检查新添加的地图点
    while(lit!=mlpRecentAddedMapPoints.end())
    {
        MapPoint* pMP = *lit;
        if(pMP->isBad())
        {
            // Step 2.1:已经是坏点的地图点仅从队列中删除
            lit = mlpRecentAddedMapPoints.erase(lit);
        }
        else if(pMP->GetFoundRatio()<0.25f)
        {
            // Step 2.2:跟踪到该地图点的帧数相比预计可观测到该地图点的帧数的比例小于25%,从地图中删除
            // (mnFound/mnVisible) < 25%
            // mnFound :地图点被多少帧(包括普通帧)看到,次数越多越好
            // mnVisible:地图点应该被看到的次数
            // (mnFound/mnVisible):对于大FOV镜头这个比例会高,对于窄FOV镜头这个比例会低
            pMP->SetBadFlag();
            lit = mlpRecentAddedMapPoints.erase(lit);
        }
        else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=2 && pMP->Observations()<=cnThObs)
        {
            // Step 2.3:从该点建立开始,到现在已经过了不小于2个关键帧
            // 但是观测到该点的相机数却不超过阈值cnThObs,从地图中删除
            pMP->SetBadFlag();
            lit = mlpRecentAddedMapPoints.erase(lit);
        }
        else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=3)
            // Step 2.4:从建立该点开始,已经过了3个关键帧而没有被剔除,则认为是质量高的点
            // 因此没有SetBadFlag(),仅从队列中删除
            lit = mlpRecentAddedMapPoints.erase(lit);
        else
            lit++;
    }
}

4 创建新地图点

该步骤主要是成员函数void LocalMapping::CreateNewMapPoints()实现的,主要实现的步骤如下:

  1. 根据相机类型设置不同的搜索最佳共视关键帧的数目nn单目设置为20双目/RGBD设置10
  2. 在当前关键帧的共视关键帧中找到共视程度最高的nn帧相邻关键帧;
  3. 遍历相邻关键帧,搜索匹配并用极线约束剔除误匹配,最终三角化;
  4. 判断相机运动的基线是不是足够长;
  5. 根据两个关键帧的位姿计算它们之间的基础矩阵;
  6. 通过词袋对两关键帧的未匹配的特征点快速匹配,用极线约束抑制离群点,生成新的匹配点对;
  7. 对每对匹配通过三角化生成3D点,和Initializer::Triangulate函数差不多;
// 用当前关键帧与相邻关键帧通过三角化产生新的地图点,使得跟踪更稳

void LocalMapping::CreateNewMapPoints()
{
    // Retrieve neighbor keyframes in covisibility graph
    // nn表示搜索最佳共视关键帧的数目
    // 不同传感器下要求不一样,单目的时候需要有更多的具有较好共视关系的关键帧来建立地图
    int nn = 10;
    if(mbMonocular)
        nn=20;

    // Step 1:在当前关键帧的共视关键帧中找到共视程度最高的nn帧相邻关键帧
    const vector<KeyFrame*> vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn);

    // 特征点匹配配置 最佳距离 < 0.6*次佳距离,比较苛刻了。不检查旋转
    ORBmatcher matcher(0.6,false); 

    // 取出当前帧从世界坐标系到相机坐标系的变换矩阵
    cv::Mat Rcw1 = mpCurrentKeyFrame->GetRotation();
    cv::Mat Rwc1 = Rcw1.t();
    cv::Mat tcw1 = mpCurrentKeyFrame->GetTranslation();
    cv::Mat Tcw1(3,4,CV_32F);
    Rcw1.copyTo(Tcw1.colRange(0,3));
    tcw1.copyTo(Tcw1.col(3));

    // 得到当前关键帧(左目)光心在世界坐标系中的坐标、内参
    cv::Mat Ow1 = mpCurrentKeyFrame->GetCameraCenter();
    const float &fx1 = mpCurrentKeyFrame->fx;
    const float &fy1 = mpCurrentKeyFrame->fy;
    const float &cx1 = mpCurrentKeyFrame->cx;
    const float &cy1 = mpCurrentKeyFrame->cy;
    const float &invfx1 = mpCurrentKeyFrame->invfx;
    const float &invfy1 = mpCurrentKeyFrame->invfy;

    // 用于后面的点深度的验证;这里的1.5是经验值
    // mfScaleFactor = 1.2
    const float ratioFactor = 1.5f*mpCurrentKeyFrame->mfScaleFactor;

    // 记录三角化成功的地图点数目
    int nnew=0;

    // Search matches with epipolar restriction and triangulate
    // Step 2:遍历相邻关键帧,搜索匹配并用极线约束剔除误匹配,最终三角化
    for(size_t i=0; i<vpNeighKFs.size(); i++)
    {
        // ! 疑似bug,正确应该是 if(i>0 && !CheckNewKeyFrames())
        if(i>0 && CheckNewKeyFrames())
            return;

        KeyFrame* pKF2 = vpNeighKFs[i];

        // Check first that baseline is not too short
        // 相邻的关键帧光心在世界坐标系中的坐标
        cv::Mat Ow2 = pKF2->GetCameraCenter();
        // 基线向量,两个关键帧间的相机位移
        cv::Mat vBaseline = Ow2-Ow1;
        // 基线长度
        const float baseline = cv::norm(vBaseline);

        // Step 3:判断相机运动的基线是不是足够长
        if(!mbMonocular)
        {
            // 如果是双目相机,关键帧间距小于本身的基线时不生成3D点
            // 因为太短的基线下能够恢复的地图点不稳定
            if(baseline<pKF2->mb)
            continue;
        }
        else    
        {
            // 单目相机情况
            // 相邻关键帧的场景深度中值
            const float medianDepthKF2 = pKF2->ComputeSceneMedianDepth(2);
            // 基线与景深的比例
            const float ratioBaselineDepth = baseline/medianDepthKF2;
            // 如果比例特别小,基线太短恢复3D点不准,那么跳过当前邻接的关键帧,不生成3D点
            if(ratioBaselineDepth<0.01)
                continue;
        }

        // Compute Fundamental Matrix
        // Step 4:根据两个关键帧的位姿计算它们之间的基础矩阵
        cv::Mat F12 = ComputeF12(mpCurrentKeyFrame,pKF2);

        // Search matches that fullfil epipolar constraint
        // Step 5:通过词袋对两关键帧的未匹配的特征点快速匹配,用极线约束抑制离群点,生成新的匹配点对
        vector<pair<size_t,size_t> > vMatchedIndices;
        matcher.SearchForTriangulation(mpCurrentKeyFrame,pKF2,F12,vMatchedIndices,false);

        cv::Mat Rcw2 = pKF2->GetRotation();
        cv::Mat Rwc2 = Rcw2.t();
        cv::Mat tcw2 = pKF2->GetTranslation();
        cv::Mat Tcw2(3,4,CV_32F);
        Rcw2.copyTo(Tcw2.colRange(0,3));
        tcw2.copyTo(Tcw2.col(3));

        const float &fx2 = pKF2->fx;
        const float &fy2 = pKF2->fy;
        const float &cx2 = pKF2->cx;
        const float &cy2 = pKF2->cy;
        const float &invfx2 = pKF2->invfx;
        const float &invfy2 = pKF2->invfy;

        // Triangulate each match
        // Step 6:对每对匹配通过三角化生成3D点,和 Triangulate函数差不多
        const int nmatches = vMatchedIndices.size();
        for(int ikp=0; ikp<nmatches; ikp++) 
        {
            // Step 6.1:取出匹配特征点

            // 当前匹配对在当前关键帧中的索引
            const int &idx1 = vMatchedIndices[ikp].first;
            
            // 当前匹配对在邻接关键帧中的索引
            const int &idx2 = vMatchedIndices[ikp].second;

            // 当前匹配在当前关键帧中的特征点
            const cv::KeyPoint &kp1 = mpCurrentKeyFrame->mvKeysUn[idx1];
            // mvuRight中存放着双目的深度值,如果不是双目,其值将为-1
            const float kp1_ur=mpCurrentKeyFrame->mvuRight[idx1];
            bool bStereo1 = kp1_ur>=0;

            // 当前匹配在邻接关键帧中的特征点
            const cv::KeyPoint &kp2 = pKF2->mvKeysUn[idx2];
            // mvuRight中存放着双目的深度值,如果不是双目,其值将为-1
            const float kp2_ur = pKF2->mvuRight[idx2];
            bool bStereo2 = kp2_ur>=0;

            // Check parallax between rays
            // Step 6.2:利用匹配点反投影得到视差角
            // 特征点反投影,其实得到的是在各自相机坐标系下的一个非归一化的方向向量,和这个点的反投影射线重合
            cv::Mat xn1 = (cv::Mat_<float>(3,1) << (kp1.pt.x-cx1)*invfx1, (kp1.pt.y-cy1)*invfy1, 1.0);
            cv::Mat xn2 = (cv::Mat_<float>(3,1) << (kp2.pt.x-cx2)*invfx2, (kp2.pt.y-cy2)*invfy2, 1.0);

            // 由相机坐标系转到世界坐标系(得到的是那条反投影射线的一个同向向量在世界坐标系下的表示,还是只能够表示方向),得到视差角余弦值
            cv::Mat ray1 = Rwc1*xn1;
            cv::Mat ray2 = Rwc2*xn2;
            // 匹配点射线夹角余弦值
            const float cosParallaxRays = ray1.dot(ray2)/(cv::norm(ray1)*cv::norm(ray2));

            // 加1是为了让cosParallaxStereo随便初始化为一个很大的值
            float cosParallaxStereo = cosParallaxRays+1;  
            // cosParallaxStereo1、cosParallaxStereo2在后面可能不存在,需要初始化为较大的值
            float cosParallaxStereo1 = cosParallaxStereo;
            float cosParallaxStereo2 = cosParallaxStereo;

            // Step 6.3:对于双目,利用双目得到视差角;单目相机没有特殊操作
            if(bStereo1)
                // 传感器是双目相机,并且当前的关键帧的这个点有对应的深度
                // 假设是平行的双目相机,计算出双目相机观察这个点的时候的视差角余弦
                cosParallaxStereo1 = cos(2*atan2(mpCurrentKeyFrame->mb/2,mpCurrentKeyFrame->mvDepth[idx1]));
            else if(bStereo2)
                // 传感器是双目相机,并且邻接的关键帧的这个点有对应的深度,和上面一样操作
                cosParallaxStereo2 = cos(2*atan2(pKF2->mb/2,pKF2->mvDepth[idx2]));
            
            // 得到双目观测的视差角中最小的那个
            cosParallaxStereo = min(cosParallaxStereo1,cosParallaxStereo2);

            // Step 6.4:三角化恢复3D点
            cv::Mat x3D;
            // cosParallaxRays>0 && (bStereo1 || bStereo2 || cosParallaxRays<0.9998)表明视差角正常,0.9998 对应1°
            // cosParallaxRays < cosParallaxStereo 表明匹配点对夹角大于双目本身观察三维点夹角
            // 匹配点对夹角大,用三角法恢复3D点
            // 参考:https://github.com/raulmur/ORB_SLAM2/issues/345
            if(cosParallaxRays<cosParallaxStereo && cosParallaxRays>0 && (bStereo1 || bStereo2 || cosParallaxRays<0.9998))
            {
                // Linear Triangulation Method
                // 见Initializer.cc的 Triangulate 函数,实现是一样的,顶多就是把投影矩阵换成了变换矩阵
                cv::Mat A(4,4,CV_32F);
                A.row(0) = xn1.at<float>(0)*Tcw1.row(2)-Tcw1.row(0);
                A.row(1) = xn1.at<float>(1)*Tcw1.row(2)-Tcw1.row(1);
                A.row(2) = xn2.at<float>(0)*Tcw2.row(2)-Tcw2.row(0);
                A.row(3) = xn2.at<float>(1)*Tcw2.row(2)-Tcw2.row(1);

                cv::Mat w,u,vt;
                cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV);

                x3D = vt.row(3).t();
                // 归一化之前的检查
                if(x3D.at<float>(3)==0)
                    continue;
                // 归一化成为齐次坐标,然后提取前面三个维度作为欧式坐标
                x3D = x3D.rowRange(0,3)/x3D.at<float>(3);
            }
            // 匹配点对夹角小,用双目恢复3D点
            else if(bStereo1 && cosParallaxStereo1<cosParallaxStereo2)  
            {
                // 如果是双目,用视差角更大的那个双目信息来恢复,直接用已知3D点反投影了
                x3D = mpCurrentKeyFrame->UnprojectStereo(idx1);                
            }
            else if(bStereo2 && cosParallaxStereo2<cosParallaxStereo1)  
            {
                x3D = pKF2->UnprojectStereo(idx2);
            }
            else
                continue; //No stereo and very low parallax, 放弃

            // 为方便后续计算,转换成为了行向量
            cv::Mat x3Dt = x3D.t();

            //Check triangulation in front of cameras
            // Step 6.5:检测生成的3D点是否在相机前方,不在的话就放弃这个点
            float z1 = Rcw1.row(2).dot(x3Dt)+tcw1.at<float>(2);
            if(z1<=0)
                continue;

            float z2 = Rcw2.row(2).dot(x3Dt)+tcw2.at<float>(2);
            if(z2<=0)
                continue;

            //Check reprojection error in first keyframe
            // Step 6.6:计算3D点在当前关键帧下的重投影误差
            const float &sigmaSquare1 = mpCurrentKeyFrame->mvLevelSigma2[kp1.octave];
            const float x1 = Rcw1.row(0).dot(x3Dt)+tcw1.at<float>(0);
            const float y1 = Rcw1.row(1).dot(x3Dt)+tcw1.at<float>(1);
            const float invz1 = 1.0/z1;

            if(!bStereo1)
            {
                // 单目情况下
                float u1 = fx1*x1*invz1+cx1;
                float v1 = fy1*y1*invz1+cy1;
                float errX1 = u1 - kp1.pt.x;
                float errY1 = v1 - kp1.pt.y;
                // 假设测量有一个像素的偏差,2自由度卡方检验阈值是5.991
                if((errX1*errX1+errY1*errY1)>5.991*sigmaSquare1)
                    continue;
            }
            else
            {
                // 双目情况
                float u1 = fx1*x1*invz1+cx1;
                // 根据视差公式计算假想的右目坐标
                float u1_r = u1 - mpCurrentKeyFrame->mbf*invz1;     
                float v1 = fy1*y1*invz1+cy1;
                float errX1 = u1 - kp1.pt.x;
                float errY1 = v1 - kp1.pt.y;
                float errX1_r = u1_r - kp1_ur;
                // 自由度为3,卡方检验阈值是7.8
                if((errX1*errX1+errY1*errY1+errX1_r*errX1_r)>7.8*sigmaSquare1)
                    continue;
            }

            //Check reprojection error in second keyframe
            // 计算3D点在另一个关键帧下的重投影误差,操作同上
            const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave];
            const float x2 = Rcw2.row(0).dot(x3Dt)+tcw2.at<float>(0);
            const float y2 = Rcw2.row(1).dot(x3Dt)+tcw2.at<float>(1);
            const float invz2 = 1.0/z2;
            if(!bStereo2)
            {
                float u2 = fx2*x2*invz2+cx2;
                float v2 = fy2*y2*invz2+cy2;
                float errX2 = u2 - kp2.pt.x;
                float errY2 = v2 - kp2.pt.y;
                if((errX2*errX2+errY2*errY2)>5.991*sigmaSquare2)
                    continue;
            }
            else
            {
                float u2 = fx2*x2*invz2+cx2;
                float u2_r = u2 - mpCurrentKeyFrame->mbf*invz2;
                float v2 = fy2*y2*invz2+cy2;
                float errX2 = u2 - kp2.pt.x;
                float errY2 = v2 - kp2.pt.y;
                float errX2_r = u2_r - kp2_ur;
                if((errX2*errX2+errY2*errY2+errX2_r*errX2_r)>7.8*sigmaSquare2)
                    continue;
            }

            //Check scale consistency
            // Step 6.7:检查尺度连续性

            // 世界坐标系下,3D点与相机间的向量,方向由相机指向3D点
            cv::Mat normal1 = x3D-Ow1;
            float dist1 = cv::norm(normal1);

            cv::Mat normal2 = x3D-Ow2;
            float dist2 = cv::norm(normal2);

            if(dist1==0 || dist2==0)
                continue;

            // ratioDist是不考虑金字塔尺度下的距离比例
            const float ratioDist = dist2/dist1;
            // 金字塔尺度因子的比例
            const float ratioOctave = mpCurrentKeyFrame->mvScaleFactors[kp1.octave]/pKF2->mvScaleFactors[kp2.octave];

            /*if(fabs(ratioDist-ratioOctave)>ratioFactor)
                continue;*/

            // 距离的比例和图像金字塔的比例不应该差太多,否则就跳过
            if(ratioDist*ratioFactor<ratioOctave || ratioDist>ratioOctave*ratioFactor)
                continue;

            // Triangulation is succesfull
            // Step 6.8:三角化生成3D点成功,构造成MapPoint
            MapPoint* pMP = new MapPoint(x3D,mpCurrentKeyFrame,mpMap);

            // Step 6.9:为该MapPoint添加属性:
            // a.观测到该MapPoint的关键帧
            pMP->AddObservation(mpCurrentKeyFrame,idx1);            
            pMP->AddObservation(pKF2,idx2);

            mpCurrentKeyFrame->AddMapPoint(pMP,idx1);
            pKF2->AddMapPoint(pMP,idx2);

            // b.该MapPoint的描述子
            pMP->ComputeDistinctiveDescriptors();

            // c.该MapPoint的平均观测方向和深度范围
            pMP->UpdateNormalAndDepth();

            mpMap->AddMapPoint(pMP);

            // Step 6.10:将新产生的点放入检测队列
            // 这些MapPoints都会经过MapPointCulling函数的检验
            mlpRecentAddedMapPoints.push_back(pMP);

            nnew++;
        }
    }
}

5 融合当前关键帧和其共视帧的地图点

该步骤主要是通过成员函数void LocalMapping::SearchInNeighbors()实现的,这里有两个小概念需要先熟悉下:

  1. 一级相邻关键帧:当前关键帧的邻接关键帧,即当前关键帧的邻居
  2. 二级相邻关键帧:一级相邻关键帧相邻的关键帧,即当前关键帧的邻居的邻居

该函数主要实现的步骤如下:

  1. 根据相机类型设置不同的邻接关键帧数目nn单目设置为20双目/RGBD设置10
  2. 获得当前关键帧在共视图中权重排名前nn的邻接关键帧;
  3. 存储一级相邻关键帧及其二级相邻关键帧;
  4. 将当前帧的地图点分别投影到两级相邻关键帧,寻找匹配点对应的地图点进行融合,称为正向投影融合;
  5. 将两级相邻关键帧地图点分别投影到当前关键帧,寻找匹配点对应的地图点进行融合,称为反向投影融合;
  6. 更新当前帧地图点的描述子、深度、平均观测方向等属性;
  7. 最后,更新当前帧与其它帧的共视连接关系;
// 检查并融合当前关键帧与相邻帧(两级相邻)重复的地图点

void LocalMapping::SearchInNeighbors()
{
    // Retrieve neighbor keyframes
    // Step 1:获得当前关键帧在共视图中权重排名前nn的邻接关键帧
    // 开始之前先定义几个概念
    // 当前关键帧的邻接关键帧,称为一级相邻关键帧,也就是邻居
    // 与一级相邻关键帧相邻的关键帧,称为二级相邻关键帧,也就是邻居的邻居

    // 单目情况要20个邻接关键帧,双目或者RGBD则要10个
    int nn = 10;
    if(mbMonocular)
        nn=20;

    // 和当前关键帧相邻的关键帧,也就是一级相邻关键帧
    const vector<KeyFrame*> vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn);
    
    // Step 2:存储一级相邻关键帧及其二级相邻关键帧
    vector<KeyFrame*> vpTargetKFs;
    // 开始对所有候选的一级关键帧展开遍历:
    for(vector<KeyFrame*>::const_iterator vit=vpNeighKFs.begin(), vend=vpNeighKFs.end(); vit!=vend; vit++)
    {
        KeyFrame* pKFi = *vit;
        // 没有和当前帧进行过融合的操作
        if(pKFi->isBad() || pKFi->mnFuseTargetForKF == mpCurrentKeyFrame->mnId)
            continue;
        // 加入一级相邻关键帧    
        vpTargetKFs.push_back(pKFi);
        // 标记已经加入
        pKFi->mnFuseTargetForKF = mpCurrentKeyFrame->mnId;

        // Extend to some second neighbors
        // 以一级相邻关键帧的共视关系最好的5个相邻关键帧 作为二级相邻关键帧
        const vector<KeyFrame*> vpSecondNeighKFs = pKFi->GetBestCovisibilityKeyFrames(5);
        // 遍历得到的二级相邻关键帧
        for(vector<KeyFrame*>::const_iterator vit2=vpSecondNeighKFs.begin(), vend2=vpSecondNeighKFs.end(); vit2!=vend2; vit2++)
        {
            KeyFrame* pKFi2 = *vit2;
            // 当然这个二级相邻关键帧要求没有和当前关键帧发生融合,并且这个二级相邻关键帧也不是当前关键帧
            if(pKFi2->isBad() || pKFi2->mnFuseTargetForKF==mpCurrentKeyFrame->mnId || pKFi2->mnId==mpCurrentKeyFrame->mnId)
                continue;
            // 存入二级相邻关键帧    
            vpTargetKFs.push_back(pKFi2);
        }
    }

    // Search matches by projection from current KF in target KFs
    // 使用默认参数, 最优和次优比例0.6,匹配时检查特征点的旋转
    ORBmatcher matcher;

    // Step 3:将当前帧的地图点分别投影到两级相邻关键帧,寻找匹配点对应的地图点进行融合,称为正向投影融合
    vector<MapPoint*> vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
    for(vector<KeyFrame*>::iterator vit=vpTargetKFs.begin(), vend=vpTargetKFs.end(); vit!=vend; vit++)
    {
        KeyFrame* pKFi = *vit;

        // 将地图点投影到关键帧中进行匹配和融合;融合策略如下
        // 1.如果地图点能匹配关键帧的特征点,并且该点有对应的地图点,那么选择观测数目多的替换两个地图点
        // 2.如果地图点能匹配关键帧的特征点,并且该点没有对应的地图点,那么为该点添加该投影地图点
        // 注意这个时候对地图点融合的操作是立即生效的
        matcher.Fuse(pKFi,vpMapPointMatches);
    }

    // Search matches by projection from target KFs in current KF
    // Step 4:将两级相邻关键帧地图点分别投影到当前关键帧,寻找匹配点对应的地图点进行融合,称为反向投影融合
    // 用于进行存储要融合的一级邻接和二级邻接关键帧所有MapPoints的集合
    vector<MapPoint*> vpFuseCandidates;
    vpFuseCandidates.reserve(vpTargetKFs.size()*vpMapPointMatches.size());
    
    //  Step 4.1:遍历每一个一级邻接和二级邻接关键帧,收集他们的地图点存储到 vpFuseCandidates
    for(vector<KeyFrame*>::iterator vitKF=vpTargetKFs.begin(), vendKF=vpTargetKFs.end(); vitKF!=vendKF; vitKF++)
    {
        KeyFrame* pKFi = *vitKF;
        vector<MapPoint*> vpMapPointsKFi = pKFi->GetMapPointMatches();

        // 遍历当前一级邻接和二级邻接关键帧中所有的MapPoints,找出需要进行融合的并且加入到集合中
        for(vector<MapPoint*>::iterator vitMP=vpMapPointsKFi.begin(), vendMP=vpMapPointsKFi.end(); vitMP!=vendMP; vitMP++)
        {
            MapPoint* pMP = *vitMP;
            if(!pMP)
                continue;
            
            // 如果地图点是坏点,或者已经加进集合vpFuseCandidates,跳过
            if(pMP->isBad() || pMP->mnFuseCandidateForKF == mpCurrentKeyFrame->mnId)
                continue;

            // 加入集合,并标记已经加入
            pMP->mnFuseCandidateForKF = mpCurrentKeyFrame->mnId;
            vpFuseCandidates.push_back(pMP);
        }
    }
    // Step 4.2:进行地图点投影融合,和正向融合操作是完全相同的
    // 不同的是正向操作是"每个关键帧和当前关键帧的地图点进行融合",而这里的是"当前关键帧和所有邻接关键帧的地图点进行融合"
    matcher.Fuse(mpCurrentKeyFrame,vpFuseCandidates);

    // Update points
    // Step 5:更新当前帧地图点的描述子、深度、平均观测方向等属性
    vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
    for(size_t i=0, iend=vpMapPointMatches.size(); i<iend; i++)
    {
        MapPoint* pMP=vpMapPointMatches[i];
        if(pMP)
        {
            if(!pMP->isBad())
            {
                // 在所有找到pMP的关键帧中,获得最佳的描述子
                pMP->ComputeDistinctiveDescriptors();

                // 更新平均观测方向和观测距离
                pMP->UpdateNormalAndDepth();
            }
        }
    }

    // Update connections in covisibility graph
    // Step 6:更新当前帧与其它帧的共视连接关系
    mpCurrentKeyFrame->UpdateConnections();
}

6 局部BA优化

该步骤主要是通过成员函数void Optimizer::LocalBundleAdjustment()实现的,该函数不是在LocalMapping类中实现的,是Optimizer类中实现的(Optimizer.cc),主要是构造g2o优化器来实现的,详细的实现步骤如下:

  1. 关键帧选择:ORB-SLAM2中,局部BA优化是在一组关键帧上执行的。首先,根据一些准则(例如,距离、关键点数量等),选择一组具有较高质量和代表性的关键帧。
  2. 重投影误差计算:对于每个选择的关键帧,计算其观测到的地图点在其图像上的重投影位置,并计算重投影误差。重投影误差即观测到的图像点与通过当前估计的相机位姿和地图点位置计算得到的重投影点之间的差异。
  3. 优化问题建模:将局部BA问题建模为一个非线性优化问题。优化的目标是最小化重投影误差,通过调整关键帧的位姿和地图点的位置来优化。
  4. 约束设置:将关键帧的位姿和地图点的位置作为优化变量,并设置约束来限制它们的调整范围。约束通常包括相机位姿的刚性运动模型和地图点的三维空间几何关系。
  5. 优化求解:使用非线性优化方法(例如,高斯-牛顿法或Levenberg-Marquardt算法)对建立的优化问题进行求解。通过迭代优化变量的值,以最小化重投影误差。
  6. 优化结果应用:将优化后的相机位姿和地图点位置应用于系统中的关键帧和地图更新。这样可以提高相机位姿的准确性,优化地图点的位置,并进一步改善系统的精度和稳定性。
// 局部BA优化

void Optimizer::LocalBundleAdjustment(KeyFrame *pKF, bool* pbStopFlag, Map* pMap)
{
    // 该优化函数用于LocalMapping线程的局部BA优化

    // Local KeyFrames: First Breadth Search from Current Keyframe
    // 局部关键帧
    list<KeyFrame*> lLocalKeyFrames;

    // Step 1 将当前关键帧及其共视关键帧加入局部关键帧
    lLocalKeyFrames.push_back(pKF);
    pKF->mnBALocalForKF = pKF->mnId;

    // 找到关键帧连接的共视关键帧(一级相连),加入局部关键帧中
    const vector<KeyFrame*> vNeighKFs = pKF->GetVectorCovisibleKeyFrames();
    for(int i=0, iend=vNeighKFs.size(); i<iend; i++)
    {
        KeyFrame* pKFi = vNeighKFs[i];

        // 把参与局部BA的每一个关键帧的 mnBALocalForKF设置为当前关键帧的mnId,防止重复添加
        pKFi->mnBALocalForKF = pKF->mnId;

        // 保证该关键帧有效才能加入
        if(!pKFi->isBad())      
            lLocalKeyFrames.push_back(pKFi);
    }

    // Local MapPoints seen in Local KeyFrames
    // Step 2 遍历局部关键帧中(一级相连)关键帧,将它们观测的地图点加入到局部地图点
    list<MapPoint*> lLocalMapPoints;
    // 遍历局部关键帧中的每一个关键帧
    for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin() , lend=lLocalKeyFrames.end(); lit!=lend; lit++)
    {
        // 取出该关键帧对应的地图点
        vector<MapPoint*> vpMPs = (*lit)->GetMapPointMatches();
        // 遍历这个关键帧观测到的每一个地图点,加入到局部地图点
        for(vector<MapPoint*>::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++)
        {
            MapPoint* pMP = *vit;
            if(pMP)
            {
                if(!pMP->isBad())   //保证地图点有效
                    // 把参与局部BA的每一个地图点的 mnBALocalForKF设置为当前关键帧的mnId
                    // mnBALocalForKF 是为了防止重复添加
                    if(pMP->mnBALocalForKF!=pKF->mnId)
                    {
                        lLocalMapPoints.push_back(pMP);
                        pMP->mnBALocalForKF=pKF->mnId;
                    }
            }   // 判断这个地图点是否靠谱
        } // 遍历这个关键帧观测到的每一个地图点
    } // 遍历 lLocalKeyFrames 中的每一个关键帧

    // Fixed Keyframes. Keyframes that see Local MapPoints but that are not Local Keyframes
    // Step 3 得到能被局部地图点观测到,但不属于局部关键帧的关键帧(二级相连),这些二级相连关键帧在局部BA优化时不优化
    list<KeyFrame*> lFixedCameras;
    // 遍历局部地图中的每个地图点
    for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
    {
        // 观测到该地图点的KF和该地图点在KF中的索引
        map<KeyFrame*,size_t> observations = (*lit)->GetObservations();
        // 遍历所有观测到该地图点的关键帧
        for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
        {
            KeyFrame* pKFi = mit->first;

            // pKFi->mnBALocalForKF!=pKF->mnId 表示不属于局部关键帧,
            // pKFi->mnBAFixedForKF!=pKF->mnId 表示还未标记为fixed(固定的)关键帧
            if(pKFi->mnBALocalForKF!=pKF->mnId && pKFi->mnBAFixedForKF!=pKF->mnId)
            {                
                // 将局部地图点能观测到的、但是不属于局部BA范围的关键帧的mnBAFixedForKF标记为pKF(触发局部BA的当前关键帧)的mnId
                pKFi->mnBAFixedForKF=pKF->mnId;
                if(!pKFi->isBad())
                    lFixedCameras.push_back(pKFi);
            }
        }
    }

    // Setup optimizer
    // Step 4 构造g2o优化器
    g2o::SparseOptimizer optimizer;
    g2o::BlockSolver_6_3::LinearSolverType * linearSolver;

    linearSolver = new g2o::LinearSolverEigen<g2o::BlockSolver_6_3::PoseMatrixType>();

    g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver);
    // LM大法好
    g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr);
    optimizer.setAlgorithm(solver);

    // 外界设置的停止优化标志
    // 可能在 Tracking::NeedNewKeyFrame() 里置位
    if(pbStopFlag)
        optimizer.setForceStopFlag(pbStopFlag);

    // 记录参与局部BA的最大关键帧mnId
    unsigned long maxKFid = 0;

    // Set Local KeyFrame vertices
    // Step 5 添加待优化的位姿顶点:局部关键帧的位姿
    for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++)
    {
        KeyFrame* pKFi = *lit;
        g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap();
        // 设置初始优化位姿
        vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose()));
        vSE3->setId(pKFi->mnId);
        // 如果是初始关键帧,要锁住位姿不优化
        vSE3->setFixed(pKFi->mnId==0);
        optimizer.addVertex(vSE3);
        if(pKFi->mnId>maxKFid)
            maxKFid=pKFi->mnId;
    }

    // Set Fixed KeyFrame vertices
    // Step  6 添加不优化的位姿顶点:固定关键帧的位姿,注意这里调用了vSE3->setFixed(true)
    // 不优化为啥也要添加?回答:为了增加约束信息
    for(list<KeyFrame*>::iterator lit=lFixedCameras.begin(), lend=lFixedCameras.end(); lit!=lend; lit++)
    {
        KeyFrame* pKFi = *lit;
        g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap();
        vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose()));
        vSE3->setId(pKFi->mnId);
         // 所有的这些顶点的位姿都不优化,只是为了增加约束项
        vSE3->setFixed(true);  
        optimizer.addVertex(vSE3);
        if(pKFi->mnId>maxKFid)
            maxKFid=pKFi->mnId;
    }

    // Set MapPoint vertices
    // Step  7 添加待优化的局部地图点顶点
    // 边的最大数目 = 位姿数目 * 地图点数目
    const int nExpectedSize = (lLocalKeyFrames.size()+lFixedCameras.size())*lLocalMapPoints.size();

    vector<g2o::EdgeSE3ProjectXYZ*> vpEdgesMono;
    vpEdgesMono.reserve(nExpectedSize);

    vector<KeyFrame*> vpEdgeKFMono;
    vpEdgeKFMono.reserve(nExpectedSize);

    vector<MapPoint*> vpMapPointEdgeMono;
    vpMapPointEdgeMono.reserve(nExpectedSize);

    vector<g2o::EdgeStereoSE3ProjectXYZ*> vpEdgesStereo;
    vpEdgesStereo.reserve(nExpectedSize);

    vector<KeyFrame*> vpEdgeKFStereo;
    vpEdgeKFStereo.reserve(nExpectedSize);

    vector<MapPoint*> vpMapPointEdgeStereo;
    vpMapPointEdgeStereo.reserve(nExpectedSize);

    // 自由度为2的卡方分布,显著性水平为0.05,对应的临界阈值5.991
    const float thHuberMono = sqrt(5.991);

    // 自由度为3的卡方分布,显著性水平为0.05,对应的临界阈值7.815
    const float thHuberStereo = sqrt(7.815);

    // 遍历所有的局部地图点
    for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
    {
        // 添加顶点:MapPoint
        MapPoint* pMP = *lit;
        g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ();
        vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos()));
        // 前面记录maxKFid的作用在这里体现
        int id = pMP->mnId+maxKFid+1;
        vPoint->setId(id);
        // 因为使用了LinearSolverType,所以需要将所有的三维点边缘化掉
        vPoint->setMarginalized(true);  
        optimizer.addVertex(vPoint);

        // 观测到该地图点的KF和该地图点在KF中的索引
        const map<KeyFrame*,size_t> observations = pMP->GetObservations();

        // Set edges
        // Step 8 在添加完了一个地图点之后, 对每一对关联的地图点和关键帧构建边
        // 遍历所有观测到当前地图点的关键帧
        for(map<KeyFrame*,size_t>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
        {
            KeyFrame* pKFi = mit->first;

            if(!pKFi->isBad())
            {                
                const cv::KeyPoint &kpUn = pKFi->mvKeysUn[mit->second];
                // 根据单目/双目两种不同的输入构造不同的误差边
                // Monocular observation
                // 单目模式下
                if(pKFi->mvuRight[mit->second]<0)
                {
                    Eigen::Matrix<double,2,1> obs;
                    obs << kpUn.pt.x, kpUn.pt.y;

                    g2o::EdgeSE3ProjectXYZ* e = new g2o::EdgeSE3ProjectXYZ();
                    // 边的第一个顶点是地图点
                    e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id)));
                    // 边的第一个顶点是观测到该地图点的关键帧
                    e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pKFi->mnId)));
                    e->setMeasurement(obs);
                    // 权重为特征点所在图像金字塔的层数的倒数
                    const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave];
                    e->setInformation(Eigen::Matrix2d::Identity()*invSigma2);

                    // 使用鲁棒核函数抑制外点
                    g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber;
                    e->setRobustKernel(rk);
                    rk->setDelta(thHuberMono);

                    e->fx = pKFi->fx;
                    e->fy = pKFi->fy;
                    e->cx = pKFi->cx;
                    e->cy = pKFi->cy;
                    // 将边添加到优化器,记录边、边连接的关键帧、边连接的地图点信息
                    optimizer.addEdge(e);
                    vpEdgesMono.push_back(e);
                    vpEdgeKFMono.push_back(pKFi);
                    vpMapPointEdgeMono.push_back(pMP);
                }
                else // Stereo observation
                {
                    // 双目或RGB-D模式和单目模式类似
                    Eigen::Matrix<double,3,1> obs;
                    const float kp_ur = pKFi->mvuRight[mit->second];
                    obs << kpUn.pt.x, kpUn.pt.y, kp_ur;

                    g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ();

                    e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id)));
                    e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pKFi->mnId)));
                    e->setMeasurement(obs);
                    const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave];
                    Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2;
                    e->setInformation(Info);

                    g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber;
                    e->setRobustKernel(rk);
                    rk->setDelta(thHuberStereo);

                    e->fx = pKFi->fx;
                    e->fy = pKFi->fy;
                    e->cx = pKFi->cx;
                    e->cy = pKFi->cy;
                    e->bf = pKFi->mbf;

                    optimizer.addEdge(e);
                    vpEdgesStereo.push_back(e);
                    vpEdgeKFStereo.push_back(pKFi);
                    vpMapPointEdgeStereo.push_back(pMP);
                } 
            } 
        } // 遍历所有观测到当前地图点的关键帧
    } // 遍历所有的局部地图中的地图点

    // 开始BA前再次确认是否有外部请求停止优化,因为这个变量是引用传递,会随外部变化
    // 可能在 Tracking::NeedNewKeyFrame(), mpLocalMapper->InsertKeyFrame 里置位
    if(pbStopFlag)
        if(*pbStopFlag)
            return;

    // Step 9 分成两个阶段开始优化。
    // 第一阶段优化
    optimizer.initializeOptimization();
    // 迭代5次
    optimizer.optimize(5);  

    bool bDoMore= true;

    // 检查是否外部请求停止
    if(pbStopFlag)
        if(*pbStopFlag)
            bDoMore = false;

    // 如果有外部请求停止,那么就不在进行第二阶段的优化
    if(bDoMore)
    {
        // Check inlier observations
        // Step 10 检测outlier,并设置下次不优化
        // 遍历所有的单目误差边
        for(size_t i=0, iend=vpEdgesMono.size(); i<iend;i++)
        {
            g2o::EdgeSE3ProjectXYZ* e = vpEdgesMono[i];
            MapPoint* pMP = vpMapPointEdgeMono[i];

            if(pMP->isBad())
                continue;

            // 基于卡方检验计算出的阈值(假设测量有一个像素的偏差)
            // 自由度为2的卡方分布,显著性水平为0.05,对应的临界阈值5.991
            // 如果 当前边误差超出阈值,或者边链接的地图点深度值为负,说明这个边有问题,不优化了。
            if(e->chi2()>5.991 || !e->isDepthPositive())
            {
                // 不优化
                e->setLevel(1);
            }
            // 第二阶段优化的时候就属于精求解了,所以就不使用核函数
            e->setRobustKernel(0);
        }

        // 对于所有的双目的误差边也都进行类似的操作
        for(size_t i=0, iend=vpEdgesStereo.size(); i<iend;i++)
        {
            g2o::EdgeStereoSE3ProjectXYZ* e = vpEdgesStereo[i];
            MapPoint* pMP = vpMapPointEdgeStereo[i];

            if(pMP->isBad())
                continue;
            // 自由度为3的卡方分布,显著性水平为0.05,对应的临界阈值7.815
            if(e->chi2()>7.815 || !e->isDepthPositive())
            {
                e->setLevel(1);
            }

            e->setRobustKernel(0);
        }

        // Optimize again without the outliers
        // Step 11:排除误差较大的outlier后再次优化 -- 第二阶段优化
        optimizer.initializeOptimization(0);
        optimizer.optimize(10);

    }

    vector<pair<KeyFrame*,MapPoint*> > vToErase;
    vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size());

    // Check inlier observations
    // Step 12:在优化后重新计算误差,剔除连接误差比较大的关键帧和地图点
    // 对于单目误差边
    for(size_t i=0, iend=vpEdgesMono.size(); i<iend;i++)
    {
        g2o::EdgeSE3ProjectXYZ* e = vpEdgesMono[i];
        MapPoint* pMP = vpMapPointEdgeMono[i];

        if(pMP->isBad())
            continue;

        // 基于卡方检验计算出的阈值(假设测量有一个像素的偏差)
        // 自由度为2的卡方分布,显著性水平为0.05,对应的临界阈值5.991
        // 如果 当前边误差超出阈值,或者边链接的地图点深度值为负,说明这个边有问题,要删掉了
        if(e->chi2()>5.991 || !e->isDepthPositive())
        {
            // outlier
            KeyFrame* pKFi = vpEdgeKFMono[i];
            vToErase.push_back(make_pair(pKFi,pMP));
        }
    }

    // 双目误差边
    for(size_t i=0, iend=vpEdgesStereo.size(); i<iend;i++)
    {
        g2o::EdgeStereoSE3ProjectXYZ* e = vpEdgesStereo[i];
        MapPoint* pMP = vpMapPointEdgeStereo[i];

        if(pMP->isBad())
            continue;

        if(e->chi2()>7.815 || !e->isDepthPositive())
        {
            KeyFrame* pKFi = vpEdgeKFStereo[i];
            vToErase.push_back(make_pair(pKFi,pMP));
        }
    }

    // Get Map Mutex
    unique_lock<mutex> lock(pMap->mMutexMapUpdate);

    // 删除点
    // 连接偏差比较大,在关键帧中剔除对该地图点的观测
    // 连接偏差比较大,在地图点中剔除对该关键帧的观测
    if(!vToErase.empty())
    {
        for(size_t i=0;i<vToErase.size();i++)
        {
            KeyFrame* pKFi = vToErase[i].first;
            MapPoint* pMPi = vToErase[i].second;
            pKFi->EraseMapPointMatch(pMPi);
            pMPi->EraseObservation(pKFi);
        }
    }

    // Recover optimized data
    // Step 13:优化后更新关键帧位姿以及地图点的位置、平均观测方向等属性

    //Keyframes
    for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++)
    {
        KeyFrame* pKF = *lit;
        g2o::VertexSE3Expmap* vSE3 = static_cast<g2o::VertexSE3Expmap*>(optimizer.vertex(pKF->mnId));
        g2o::SE3Quat SE3quat = vSE3->estimate();
        pKF->SetPose(Converter::toCvMat(SE3quat));
    }

    //Points
    for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
    {
        MapPoint* pMP = *lit;
        g2o::VertexSBAPointXYZ* vPoint = static_cast<g2o::VertexSBAPointXYZ*>(optimizer.vertex(pMP->mnId+maxKFid+1));
        pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate()));
        pMP->UpdateNormalAndDepth();
    }
}

7 剔除冗余关键帧

该步骤主要是通过成员函数void LocalMapping::KeyFrameCulling()实现的,该函数的主要变量如下表:

成员变量定义
mpCurrentKeyFrame当前关键帧,本程序就是判断它是否需要删除
pKFmpCurrentKeyFrame的某一个共视关键帧
vpMapPointspKF对应的所有地图点
pMPvpMapPoints中的某个地图点
observations所有能观测到pMP的关键帧
pKFiobservations中的某个关键帧
scaleLevelipKFi的金字塔尺度
scaleLevelpKF的金字塔尺度

冗余关键帧的判定标准是:

  • 90%以上的地图点能被其他关键帧(至少3个)观测到。

详细的实现步骤如下:

  1. 根据共视图提取当前关键帧的所有共视关键帧;
  2. 提取每个共视关键帧的地图点;
  3. 遍历该共视关键帧的所有地图点,其中能被其它至少3个关键帧观测到的地图点为冗余地图点;
  4. 如果该关键帧90%以上的有效地图点被判断为冗余的,则认为该关键帧是冗余的,需要删除该关键帧。
// 检测当前关键帧在共视图中的关键帧,根据地图点在共视图中的冗余程度剔除该共视关键帧

void LocalMapping::KeyFrameCulling()
{

    // Step 1:根据共视图提取当前关键帧的所有共视关键帧
    vector<KeyFrame*> vpLocalKeyFrames = mpCurrentKeyFrame->GetVectorCovisibleKeyFrames();

    // 对所有的共视关键帧进行遍历
    for(vector<KeyFrame*>::iterator vit=vpLocalKeyFrames.begin(), vend=vpLocalKeyFrames.end(); vit!=vend; vit++)
    {
        KeyFrame* pKF = *vit;
        // 第1个关键帧不能删除,跳过
        if(pKF->mnId==0)
            continue;
        // Step 2:提取每个共视关键帧的地图点
        const vector<MapPoint*> vpMapPoints = pKF->GetMapPointMatches();

        // 记录某个点被观测次数,后面并未使用
        int nObs = 3;                     
        // 观测次数阈值,默认为3
        const int thObs=nObs;               
        // 记录冗余观测点的数目
        int nRedundantObservations=0;     
                                                                                      
        int nMPs=0;            

        // Step 3:遍历该共视关键帧的所有地图点,其中能被其它至少3个关键帧观测到的地图点为冗余地图点
        for(size_t i=0, iend=vpMapPoints.size(); i<iend; i++)
        {
            MapPoint* pMP = vpMapPoints[i];
            if(pMP)
            {
                if(!pMP->isBad())
                {
                    if(!mbMonocular)
                    {
                        // 对于双目或RGB-D,仅考虑近处(不超过基线的40倍 )的地图点
                        if(pKF->mvDepth[i]>pKF->mThDepth || pKF->mvDepth[i]<0)
                            continue;
                    }

                    nMPs++;
                    // pMP->Observations() 是观测到该地图点的相机总数目(单目1,双目2)
                    if(pMP->Observations()>thObs)
                    {
                        const int &scaleLevel = pKF->mvKeysUn[i].octave;
                        // Observation存储的是可以看到该地图点的所有关键帧的集合
                        const map<KeyFrame*, size_t> observations = pMP->GetObservations();

                        int nObs=0;
                        // 遍历观测到该地图点的关键帧
                        for(map<KeyFrame*, size_t>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
                        {
                            KeyFrame* pKFi = mit->first;
                            if(pKFi==pKF)
                                continue;
                            const int &scaleLeveli = pKFi->mvKeysUn[mit->second].octave;

                            // 尺度约束:为什么pKF 尺度+1 要大于等于 pKFi 尺度?
                            // 回答:因为同样或更低金字塔层级的地图点更准确
                            if(scaleLeveli<=scaleLevel+1)
                            {
                                nObs++;
                                // 已经找到3个满足条件的关键帧,就停止不找了
                                if(nObs>=thObs)
                                    break;
                            }
                        }
                        // 地图点至少被3个关键帧观测到,就记录为冗余点,更新冗余点计数数目
                        if(nObs>=thObs)
                        {
                            nRedundantObservations++;
                        }
                    }
                }
            }
        }

        // Step 4:如果该关键帧90%以上的有效地图点被判断为冗余的,则认为该关键帧是冗余的,需要删除该关键帧
        if(nRedundantObservations>0.9*nMPs)
            pKF->SetBadFlag();
    }
}

Reference:

  1. https://github.com/raulmur/ORB_SLAM2
  2. https://github.com/electech6/ORB_SLAM2_detailed_comments/tree/master



须知少时凌云志,曾许人间第一流。



⭐️👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍👍🌔

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/979939.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

如何使用SpringCloud Eureka 创建单机Eureka Server-注册中心

&#x1f600;前言 本篇博文是关于使用SpringCloud Eureka 创建单机Eureka Server-注册中心&#xff0c;希望你能够喜欢 &#x1f3e0;个人主页&#xff1a;晨犀主页 &#x1f9d1;个人简介&#xff1a;大家好&#xff0c;我是晨犀&#xff0c;希望我的文章可以帮助到大家&…

Jenkins实现基础CD操作

操作截图 在Jenkins里面设置通过标签进行构建 在Jenkins中进入项目&#xff0c;配置以下 将execute shell换到invoke top-level maven targets之前 在gitlab中配置标签 代码迭代新的版本 项目代码迭代 修改docker-compose.yml 提交新版本的代码 在Jenkins中追加新…

Java调用Web Service接口

方法1. 用IDEA生成相关代码调用方法。 在IDEA插件商店下载插件 然后新建一个Java项目 创建一个包来存放生成的代码&#xff0c;(点击一下)选中这个包&#xff0c;点击Tools 填入接口url&#xff0c;记住后面拼接“?wsdl”&#xff0c;选择生成方法&#xff0c;然后OK即可生…

如何重构大数据时代中小企业的信用评价指标体系?

在大数据时代&#xff0c;中小企业信用评价具有重要的意义。中小企业是经济社会发展的重要力量&#xff0c;他们对就业、经济增长和创新发挥着重要作用。然而&#xff0c;中小企业信用评价面临各种挑战&#xff0c;比如&#xff0c;中小企业融资难的原因就在于信用评价难&#…

nginx-QPS限制

漏桶算法&#xff1a; 通过nginx配置实现QPS限速。 #设置请求并发量 qps1&#xff0c;不设置burst&#xff0c;会同时处理并发的请求&#xff0c;但是由于我们只设置了1个qps&#xff0c;所以同一时间内的请求&#xff0c;只有一个是正常的&#xff0c;其他都是失败的。 http配…

andriod studio 手机模拟器中的文件导出方法

阅读前请看一下&#xff1a;我是一个热衷于记录的人&#xff0c;每次写博客会反复研读&#xff0c;尽量不断提升博客质量。文章设置为仅粉丝可见&#xff0c;是因为写博客确实花了不少精力。希望互相进步谢谢&#xff01;&#xff01; 文章目录 阅读前请看一下&#xff1a;我是…

让你的编程之路更加顺畅——推荐一款前端编程神器

引子&#xff1a;在当今的数字化时代&#xff0c;编程已经成为一种不可或缺的技能。而前端开发&#xff0c;作为整个应用程序的“门面”&#xff0c;更是需要开发人员具备优秀的网页设计和编程能力。今天&#xff0c;我要向大家推荐一款专门为前端开发者打造的APP&#xff0c;它…

leetcode LCR 007 mid. 三数之和。对撞指针解法

题目 算法 对撞指针。双指针的一种&#xff0c;特点是一前一后&#xff0c;相向而行&#xff0c;两个指针相遇时为终点 code var threeSum function(nums) {let len nums.lengthnums.sort((a,b) > a-b)// 元素不足3个, 或 最小值>0 或 最大值<0&#xff0c;不会出…

插件_创蓝图文滑动验证码

目录 [1] 准备工作[2]使用1(1) 引入验证码js(2) 定义button引入js(3)在恰当的时机调起验证图(4) 校验之后的回调 [3] 使用2(1) 引入验证码js(2) 定义Captcha构造函数引入js(3)在恰当的时机调起验证图(4) 校验之后的回调 在进行低价秒杀时需要做一个人机校验防止机器抢购&#x…

切分支解决切不走因为未合并的路径如何解决

改代码的时候改做分支了&#xff0c;本来是在另一个分支上面改代码&#xff0c;结果改到另一个放置上面&#xff0c;然后想着使用git stash进行保存&#xff0c;然后切到另外一个分支再pop&#xff0c;结果不行。 报这个错误&#xff0c;导致切不过去&#xff0c;因为我这边pop…

SpringMVC常用注解、参数传递、返回值

目录 前言 一、常用注解 二、参数传递 ​编辑 1. 基础类型String类型 2. 复杂类型 3. RequestParam 4. PathVariable 5.RequestBody 6. RequestHeader 三、方法返回值 一&#xff1a;void 二&#xff1a;String 三&#xff1a;Stringmodel 四&#xff1a;ModelAndVi…

【HCIE】01.IGP高级特性

高级特性&#xff1a;一条命令解决一个问题 OSPF快速收敛机制 发生故障重新计算拓扑的过程叫做收敛&#xff0c;设备现在本身就是PRC算法和I-SPF算法 PRC&#xff08;针对叶子节点&#xff0c;叶子代表路由&#xff09; 不需要命令配置&#xff0c;就是ospf的特性&#xff…

我国智慧燃气建设应用过程中,有哪些关键问题?

关键词&#xff1a;智慧燃气、智慧燃气系统、智能燃气、燃气智能管控、数字孪生、智慧燃气平台 国内智慧燃气建设应用过程中需要解决以下4个关键问题&#xff1a; 01 广泛生产单元的感知能力建设方面的问题 智慧燃气的核心特征是“智慧”&#xff0c;具备“三个实现”即实现…

【AI Agent】Agent的原理介绍与应用发展思考

文章目录 Agent是什么&#xff1f;最直观的公式Agent决策流程 Agent 大爆发人是如何做事的&#xff1f;如何让LLM替代人去做事?来自斯坦福的虚拟小镇架构记忆&#xff08;Memory&#xff09;反思&#xff08;Reflection&#xff09;计划&#xff08;Plan&#xff09; 类 LangC…

pycharm创建py文件时自动添加基础信息--模板

在图片中加入下面基本信息&#xff0c;这些基本信息可以自己定义&#xff1a; #!/usr/bin/env python # -*- coding: utf-8 -*- # Time : ${DATE} ${TIME} # Author : supermps # File : ${NAME}.py # Software : ${PRODUCT_NAME} import logging import math import w…

【群智能算法改进】一种改进的鹈鹕优化算法 IPOA算法[1]【Matlab代码#57】

文章目录 【获取资源请见文章第5节&#xff1a;资源获取】1. 原始POA算法2. 改进后的IPOA算法2.1 Sine映射种群初始化2.2 融合改进的正余弦策略2.3 Levy飞行策略 3. 部分代码展示4. 仿真结果展示5. 资源获取 【获取资源请见文章第5节&#xff1a;资源获取】 1. 原始POA算法 此…

MySQL中分区与分表的区别

MySQL中分区与分表的区别 一、分区与分表的区别 分区和分表是在处理大规模数据时的两种技术手段&#xff0c;尽管它们的目标都是提升系统的性能和数据管理的效率&#xff0c;但它们的实现方式和应用场景略有不同。 1. 分区 分区是将一个大表分割为多个更小的子表&#xff0c…

3D点云处理:点云投影为2D图像 调平点云(附源码)

文章目录 0. 测试效果1. 基本内容1.1 计算点云位姿1.2 调平点云1.3 点云投影2. 代码实现文章目录:3D视觉个人学习目录微信:dhlddxB站: Non-Stop_0. 测试效果

uniapp对接支付宝出现的问题

支付逻辑没问题却出现商家订单参数异常&#xff0c;请重新发起付款 检查发现后端传回来根本没什么问题&#xff0c;检查很久发现需要下载证书放在服务器上 小程序文档 - 支付宝文档中心

支付宝pc支付(springboot版),简单配置即可实现支付

概述 支付宝pc支付&#xff0c;只需要修改配置就可以实现支付&#xff0c;0基础小白都可以用。使用springboot编写&#xff0c;简单易用。 详细 DEMO简介 springboot整合支付宝pc支付&#xff0c;仅仅需要少量的配置&#xff0c;就可以实现pc支付。 项目截图 支付流程 用户…