ORBSLAM2中的关键帧插入判定
程序员文章站
2024-03-25 10:37:10
...
ORBSLAM2中的关键帧插入判定
如果是仅追踪模式:mbOnlyTracking
>>判定失败
如果[mpLocalMapper->mbStopped]和[mpLocalMapper->mbStoppedmbStopRequested]都是flase
>>判定失败
如果已有[关键帧数量>mMaxFrames]且[重定位后还 没有 度过mMaxFrames个帧]
>>判定失败
如果经过以上三个判断后还未判定失败,考察一下几个条件:
c1a: 上次插入关键帧后已经过去mMaxFrames个帧
c1b: [上次插入关键帧后已经过去mMinFrames个帧]且[mpLocalMapper-> mbAcceptKeyFrames ==true]
c1c:[不是单目系统]且[mnMatchesInliers<nRefMatches*0.25 || bNeedToInsertClose ]
//含义是:当前帧track的内点相比参考关键帧来说很少,并且本身track的close特征点很少,但是可以被三角化的close特征点数量足够.c1c成立说明track比较弱,有lost的风险.但通过三角化能够通过该帧生成足够的新地图点
//其中:mnMatchesInliers是其中track局部地图时当前帧中 内点中 nObs>0的特征点的数量
//其中:nRefMatches参考关键帧的mvpMapPoints中 obn大于某阈值nMinObs 的mappoint数量
//bNeedToInsertClose = (nTrackedClose<100) && (nNonTrackedClose>70);
//nMinObs = 3;但如果已有关键帧数量不超过2个,则nMinObs=2;
//nNonTrackedClose 是当前帧close特征点中 不是tack局部地图的内点 的数量
//nTrackedClose 是当前帧close特征点中 是tack局部地图的内点 的数量
c2 = [mnMatchesInliers<nRefMatches*thRefRatio|| bNeedToInsertClose]且[ mnMatchesInliers>15]
//含义是:当前帧track的内点和参考关键帧的地图点的重合度要低于一定阈值,或者本身track的close特征点不能很多,但是当前帧track的内点要多余15个以保证当前帧的位姿精度.c2是可以被判定为关键帧的所必须满足的条件
//其中,如果是双目系统thRefRatio = 0.75f(但如果已有关键帧数量不超过2个,则thRefRatio = 0.4f)
// 如果是单目系统thRefRatio = 0.9f
如果[c1a,c1b,c1c三个条件至少要满足一个]且[c2被满足]
>>如果mpLocalMapper-> mbAcceptKeyFrames==true
>>判定成功
>>如果mpLocalMapper-> mbAcceptKeyFrames==false
>>将mpLocalMapper->mbAbortBA设置为true(这一步不是判断)
>>如果[不是单目系统]且[mpLocalMapper->mlNewKeyFrames.size()<3]
>>判定成功
```c
//判断是否插入关键帧
bool Tracking::NeedNewKeyFrame()
{
if(mbOnlyTracking)//仅追踪不添加关键帧
return false;
// If Local Mapping is freezed by a Loop Closure do not insert keyframes
//如果建图模块由于回环检测被暂停
if(mpLocalMapper->isStopped() || mpLocalMapper->stopRequested())//分别返回mbStopped和mbStopRequested
return false;
const int nKFs = mpMap->KeyFramesInMap();//返回mpMap->mspKeyFrames.size(),即地图中已有关键帧的数量;mspKeyFrames是set<KeyFrame*>
// Do not insert keyframes if not enough frames have passed from last relocalisation
//(已有关键帧数量>mMaxFrames时)上次重定位后必须经过了>=mMaxFrames个帧
if(mCurrentFrame.mnId<mnLastRelocFrameId+mMaxFrames && nKFs>mMaxFrames)
return false;
// Tracked MapPoints in the reference keyframe
int nMinObs = 3;//地图点的nObs的阈值
if(nKFs<=2)
nMinObs=2;
//参考关键帧的mvpMapPoints中obn大于nMinObs的mappoint数量
int nRefMatches = mpReferenceKF->TrackedMapPoints(nMinObs);
// Local Mapping accept keyframes?
bool bLocalMappingIdle = mpLocalMapper->AcceptKeyFrames();//return mpLocalMapper-> mbAcceptKeyFrames,表示localmap是否接受关键帧,初始化为true,可以被 LocalMapping::SetAcceptKeyFrames修改
// Check how many "close" points are being tracked and how many could be potentially created.
int nNonTrackedClose = 0;//close特征点中 不是tack局部地图的内点 的数量
int nTrackedClose= 0; //close特征点中 是tack局部地图的内点 的数量
if(mSensor!=System::MONOCULAR)
{
for(int i =0; i<mCurrentFrame.N; i++)
{
if(mCurrentFrame.mvDepth[i]>0 && mCurrentFrame.mvDepth[i]<mThDepth)//是closepoint
{
if(mCurrentFrame.mvpMapPoints[i] && !mCurrentFrame.mvbOutlier[i])//track局部地图中的内点
nTrackedClose++;
else
nNonTrackedClose++;
}
}
}
bool bNeedToInsertClose = (nTrackedClose<100) && (nNonTrackedClose>70);
// Thresholds
float thRefRatio = 0.75f;
if(nKFs<2)//地图中已有关键帧不超过2个,则降低阈值
thRefRatio = 0.4f;
if(mSensor==System::MONOCULAR)
thRefRatio = 0.9f;
// Condition 1a: More than "MaxFrames" have passed from last keyframe insertion
const bool c1a = mCurrentFrame.mnId>=mnLastKeyFrameId+mMaxFrames;
// Condition 1b: More than "MinFrames" have passed and Local Mapping is idle
const bool c1b = (mCurrentFrame.mnId>=mnLastKeyFrameId+mMinFrames && bLocalMappingIdle);
//Condition 1c: tracking is weak
const bool c1c = mSensor!=System::MONOCULAR && (mnMatchesInliers<nRefMatches*0.25 || bNeedToInsertClose) ;
// Condition 2: Few tracked points compared to reference keyframe. Lots of visual odometry compared to map matches.
const bool c2 = ((mnMatchesInliers<nRefMatches*thRefRatio|| bNeedToInsertClose) && mnMatchesInliers>15);
if((c1a||c1b||c1c)&&c2)
{
// If the mapping accepts keyframes, insert keyframe.
// Otherwise send a signal to interrupt BA
if(bLocalMappingIdle)//表示localmap是否接受关键帧
{
return true;
}
else
{
mpLocalMapper->InterruptBA();//设置mpLocalMapper->mbAbortBA = true;
if(mSensor!=System::MONOCULAR)
{
if(mpLocalMapper->KeyframesInQueue()<3)//返回mlNewKeyFrames.size()
return true;
else
return false;
}
else
return false;
}
}
else
return false;
}
上一篇: opencv
推荐阅读
-
ORBSLAM2中的关键帧插入判定
-
CSS3中的关键帧@keyframes 和 动画animation
-
insertAdjacentElement》在dom中插入的位置
-
Django中如何批量快速的插入数据
-
将新元素插入到已排序的数组中
-
从结果集中创建一个新的表,并将结果集的内容插入到新表中 博客分类: SQL sql复制表
-
从结果集中创建一个新的表,并将结果集的内容插入到新表中 博客分类: SQL sql复制表
-
用JDBC中的Blob向oracle中插入和读取图片信息
-
在java商城开发中map集合的应用 博客分类: 互联网Java hashmaptreemapjavaobject插入
-
在给定的一维已排序(升序)数组中寻找插入一个元素的位置