初始化关键帧更新共视关系,尺度归一化

ORB-SLAM2


ORB-SLAM2初始化关键帧更新共视关系,尺度归一化


代码

// Update Connections更新初始帧与当前帧的连接关系,3D点 与关键帧建立边,每个边有一个权重,权重是该关键帧与当前帧公共3D点的个数
    pKFini->UpdateConnections();
    pKFcur->UpdateConnections();

进入UpdateConnections

void KeyFrame::UpdateConnections()
{
    map<KeyFrame*,int> KFcounter;//关键帧-权重

    vector<MapPoint*> vpMP;//3d点

    {
        unique_lock<mutex> lockMPs(mMutexFeatures);
        vpMP = mvpMapPoints;//将3d点传给vpMP
    }

    //For all map points in keyframe check in which other keyframes are they seen
    //Increase counter for those keyframes
    //统计每一个地图点有多少个关键帧,并于当前关键帧存在共视关系
    for(vector<MapPoint*>::iterator vit=vpMP.begin(), vend=vpMP.end(); vit!=vend; vit++)//遍历所有3d点,统计每一个地图点有有多少关键帧,与当前帧有共视关系
    {
        MapPoint* pMP = *vit;//取出地图点

        if(!pMP)
            continue;

        if(pMP->isBad())
            continue;

        map<KeyFrame*,size_t> observations = pMP->GetObservations();//这个3D点所有的观测

        for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)//开始迭代这个3D点对应的所有观测
        {
            if(mit->first->mnId==mnId)//如果这个观测帧是本身,continue
                continue;
            KFcounter[mit->first]++;//否则的话将对应的特征值的int++
        }
    }


	if(KFcounter.empty())//如果没有连接的就返回
        return;
	
	int nmax=0;
    KeyFrame* pKFmax=NULL;
    int th = 15;//设定个阈值

    vector<pair<int,KeyFrame*> > vPairs;
    vPairs.reserve(KFcounter.size());
    //找到对应权重最大关键帧
    for(map<KeyFrame*,int>::iterator mit=KFcounter.begin(), mend=KFcounter.end(); mit!=mend; mit++)
    {
        if(mit->second>nmax)//如果它的边数大于最大值
        {
            nmax=mit->second;//将最大值设为这个
            pKFmax=mit->first;//将关键帧个pKFmax
        }
        if(mit->second>=th)//如果边数大于阈值
        {
            vPairs.push_back(make_pair(mit->second,mit->first));//就存在vpairs中
            (mit->first)->AddConnection(this,mit->second);
        }
    }
//如果没有连接到关键帧,则对权重最大的关键帧进行连接
    if(vPairs.empty())//如果是空的,就直接添加权重最大的
    {
        vPairs.push_back(make_pair(nmax,pKFmax));
        pKFmax->AddConnection(this,nmax);
    }

    sort(vPairs.begin(),vPairs.end());
    list<KeyFrame*> lKFs;
    list<int> lWs;
    for(size_t i=0; i<vPairs.size();i++)
    {
        lKFs.push_front(vPairs[i].second);
        lWs.push_front(vPairs[i].first);
    }

    {
        unique_lock<mutex> lockCon(mMutexConnections);

        // mspConnectedKeyFrames = spConnectedKeyFrames;
        mConnectedKeyFrameWeights = KFcounter;
        mvpOrderedConnectedKeyFrames = vector<KeyFrame*>(lKFs.begin(),lKFs.end());
        mvOrderedWeights = vector<int>(lWs.begin(), lWs.end());

        if(mbFirstConnection && mnId!=0)
        {
            mpParent = mvpOrderedConnectedKeyFrames.front();
            mpParent->AddChild(this);
            mbFirstConnection = false;
        }

    }
}
  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值