1.关键帧创建条件
函数:NeedNewKeyFrame()
- IMU未初始化时,距上一次关键帧插入间隔大于0.25秒时选择插入关键帧
- 纯定位模式不插入关键帧
- 局部建图线程停止接收关键帧时不插入(一般是被闭环检测线程占用)
- 距离上次重定位较近且当前关键帧数目还算较多不插入,阈值为图像帧率FPS
- 跟踪局部地图之后匹配较少,且很长时间没有插入关键帧时选择插入(1s)
- ORB_SLAM3考虑了IMU的不稳定性,如果当前帧和上一关键帧之间时间超过0.5秒选择插入
- ORB_SLAM3单目+IMU模式匹配点低于75或者状态为RECENTLY_LOST插入
- 情况一:IMU为未初始化,距上一次关键帧插入间隔大于0.25秒时选择插入
在ORB-SALM3中,认为在IMU初始化之前的VI跟踪系统是不稳定的,因为这时IMU不确定度会给系统的估计带来影响,此时选择保守策略,每隔极小一段时间插入一个关键帧。
// 如果是IMU模式并且当前地图中未完成IMU初始化
if((mSensor == System::IMU_MONOCULAR || mSensor == System::IMU_STEREO || mSensor == System::IMU_RGBD) && !mpAtlas->GetCurrentMap()->isImuInitialized())
{
// 如果是IMU模式,当前帧距离上一关键帧时间戳超过0.25s,则说明需要插入关键帧,不再进行后续判断
if (mSensor == System::IMU_MONOCULAR && (mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.25)
return true;
else if ((mSensor == System::IMU_STEREO || mSensor == System::IMU_RGBD) && (mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.25)
return true;
else
return false;
}
- 情况二:纯定位模式不插入关键帧
因为纯定位模式下不插入关键帧,在没有先验地图的情况下仅依赖于跟踪运动模型获取相机位姿,没有跟踪局部地图也没有回环检测,因此纯定位模式打概率跑着跑着就飘了。但是在调试过程中,在具备先验地图的情况下,跟踪参考关键帧、跟踪局部地图等均依赖于先验地图中的数据,在一些过曝或者欠曝场景、运动模糊场景又或者环境发生了变化,往往也会导致跟踪失败或者发生漂移。
以上的测试使用的纯双目下的纯定位,效果有些鸡肋;对于双目+IMU尚未尝试,有了IMU的与积分在段时间的困难场景下应该会纯定位模式应该会表现稍好一些。
if(mbOnlyTracking)
{
return false;
}
- 情况三:局部建图线程停止接收关键帧时不插入(一般是被闭环检测线程占用)
- 在检测到回环后进行修正优化位姿时需要请求停止局部建图线程,防止在矫正时又有新的关键帧插入:
void LoopClosing::CorrectLoop()
- 在子地图融合时需要对融合处的关键帧和位姿进行BA优化:
void LoopClosing::MergeLocal()
- 在子地图融合函数中,最后需要对融合处的关键帧进行本质图优化,在此之前需要停止关键帧的插入(在融合刚开始时已经停止了,大概是为了加一层保险)
- 在VI模式下的子地图融合函数中进行调用:
void LoopClosing::MergeLocal2()
- 在回环矫正函数中的全局BA优化
RunGlobalBundleAdjustment
调用停止局部建图线程的请求
if(mpLocalMapper->isStopped() || mpLocalMapper->stopRequested())
return false;
- 情况四:如果距离上一次重定位比较近,并且关键帧数目还比较多,不插入关键帧(阈值为图像帧率FPS)
if(mCurrentFrame.mnId<mnLastRelocFrameId+mMaxFrames && nKFs>mMaxFrames)
{
return false;
}
如果情况一到情况四,均没有被触发则进入到最后的判断,只要满足情况567其中一条则统一插入关键帧。
- 情况五:跟踪局部地图之后匹配较少,且很长时间没有插入关键帧时选择插入(1s)
// Condition 1a: More than "MaxFrames" have passed from last keyframe insertion
// Step 7.2:很长时间没有插入关键帧,可以插入(1s)
const bool c1a = mCurrentFrame.mnId>=mnLastKeyFrameId+mMaxFrames;
// Condition 1b: More than "MinFrames" have passed and Local Mapping is idle
// Step 7.3:满足插入关键帧的最小间隔并且localMapper处于空闲状态,可以插入
// mMinFrames????怎么是0
const bool c1b = ((mCurrentFrame.mnId>=mnLastKeyFrameId+mMinFrames) && bLocalMappingIdle); //mpLocalMapper->KeyframesInQueue() < 2);
//Condition 1c: tracking is weak
// Step 7.4:在双目,RGB-D的情况下当前帧跟踪到的点比参考关键帧的0.25倍还少,或者满足bNeedToInsertClose
const bool c1c = mSensor!=System::MONOCULAR && mSensor!=System::IMU_MONOCULAR && mSensor!=System::IMU_STEREO && mSensor!=System::IMU_RGBD && (mnMatchesInliers<nRefMatches*0.25 || bNeedToInsertClose) ;
// Condition 2: Few tracked points compared to reference keyframe. Lots of visual odometry compared to map matches.
// Step 7.5:和参考帧相比当前跟踪到的点太少 或者满足bNeedToInsertClose;同时跟踪到的内点还不能太少
const bool c2 = (((mnMatchesInliers<nRefMatches*thRefRatio || bNeedToInsertClose)) && mnMatchesInliers>15);
// Temporal condition for Inertial cases
// 新增的条件c3:单目/双目+IMU模式下,并且IMU完成了初始化(隐藏条件),当前帧和上一关键帧之间时间超过0.5秒,则c3=true
bool c3 = false;
if(mpLastKeyFrame)
{
if (mSensor==System::IMU_MONOCULAR)
{
if ((mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.5)
c3 = true;
}
else if (mSensor==System::IMU_STEREO || mSensor == System::IMU_RGBD)
{
if ((mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.5)
c3 = true;
}
}
// 新增的条件c4:单目+IMU模式下,当前帧匹配内点数在15~75之间或者是RECENTLY_LOST状态,c4=true
bool c4 = false;
if ((((mnMatchesInliers<75) && (mnMatchesInliers>15)) || mState==RECENTLY_LOST) && (mSensor == System::IMU_MONOCULAR)) // MODIFICATION_2, originally ((((mnMatchesInliers<75) && (mnMatchesInliers>15)) || mState==RECENTLY_LOST) && ((mSensor == System::IMU_MONOCULAR)))
c4=true;
else
c4=false;
// 相比ORB-SLAM2多了c3,c4
- 情况六:ORB_SLAM3考虑了IMU的不稳定性,如果当前帧和上一关键帧之间时间超过0.5秒选择插入
bool c3 = false;
if(mpLastKeyFrame)
{
if (mSensor==System::IMU_MONOCULAR)
{
if ((mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.5)
c3 = true;
}
else if (mSensor==System::IMU_STEREO || mSensor == System::IMU_RGBD)
{
if ((mCurrentFrame.mTimeStamp-mpLastKeyFrame->mTimeStamp)>=0.5)
c3 = true;
}
}
- 情况七:ORB_SLAM3单目+IMU模式匹配点低于75或者状态为RECENTLY_LOST插入
// 新增的条件c4:单目+IMU模式下,当前帧匹配内点数在15~75之间或者是RECENTLY_LOST状态,c4=true
bool c4 = false;
if ((((mnMatchesInliers<75) && (mnMatchesInliers>15)) || mState==RECENTLY_LOST) && (mSensor == System::IMU_MONOCULAR)) // MODIFICATION_2, originally ((((mnMatchesInliers<75) && (mnMatchesInliers>15)) || mState==RECENTLY_LOST) && ((mSensor == System::IMU_MONOCULAR)))
c4=true;
else
c4=false;
2.关键帧删除条件
要删除的是局部地图中当前关键帧的共视关键帧中的冗余部分,因为地图点是伴随局部地图中的关键帧存在的,会随着关键帧的删除消失在局部地图中。
如果局部地图中,当前关键帧的共视关键帧有90%的点能够被其他至少3个关键帧看到,说明这个关键帧的信息冗余,删之。