bool Tracking::TrackWithMotionModel()//匀速运动追踪模式
{
ORBmatcher matcher(0.9,true);//ORB匹配器,用于后面在当前帧上搜索与重映射之后的地图点匹配的特征点
//第一个参数是一个接受最佳匹配的系数,只有当最佳匹配点的汉明距离小于次加匹配点距离的0.9倍时才接收匹配点。
//第二个参数表示匹配特征点时是否考虑方向。
// Update last frame pose according to its reference keyframe
// Create "visual odometry" points if in Localization Mode
UpdateLastFrame();//纯定位模式下构建一个视觉里程计
mCurrentFrame.SetPose(mVelocity*mLastFrame.mTcw);//通过匀速运动估计当前帧的位姿
fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast<MapPoint*>(NULL));//
// Project points seen in previous frame
int th;//th是SearchByProjection控制搜索半径的参数
if(mSensor!=System::STEREO)
th=15;
else
th=7;
int nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,th,mSensor==System::MONOCULAR);
// If few matches, uses a wider window search
if(nmatches<20)//如果匹配点比较少
{
fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast<MapPoint*>(NULL));
nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,2*th,mSensor==System::MONOCULAR);//扩大搜索半径,搜索半径*2
}
if(nmatches<20)//如果扩大半径后匹配点还是少
return false;//宣告匀速运动模式追踪失败
// Optimize frame pose with all matches
Optimizer::PoseOptimization(&mCurrentFrame);//位姿优化
// Discard outliers
int nmatchesMap = 0;
for(int i =0; i<mCurrentFrame.N; i++)
{
if(mCurrentFrame.mvpMapPoints[i])//mvpMapPoints记录了各个特征点所对应的地图点指针
{
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++;
}
}
if(mbOnlyTracking)//如果剩下的匹配的地图点太少就认为跟丢了
{
mbVO = nmatchesMap<10;
return nmatches>20;
}
return nmatchesMap>=10;
}
ORB-SLAM2 TRACKING
最新推荐文章于 2024-05-23 09:29:54 发布