本帖原文:链接
ORB-SLAM2 代码解读系列汇总:链接
Tracking 线程运行在系统主线程中,负责对每帧图像进行特征提取、位姿估计、地图跟踪、关键帧选取等工作,可以简单理解为 SLAM 的前端里程计部分,但该线程也存在一些优化。
System SLAM()
初始化 SLAM 系统时初始化了跟踪线程mpTracker = new Tracking(this,
mpVocabulary, //字典
mpFrameDrawer, //帧绘制器
mpMapDrawer, //地图绘制器
mpMap, //地图
mpKeyFrameDatabase, //关键帧地图
strSettingsFile, //配置文件路径
mSensor); //传感器类型
Tracking.cc
的 Tracking()
构造函数中主要初始化系统的一些参数,包括加载相机参数、创建 ORB 特征提取器
// 如果是双目,tracking 过程中还会用用到 mpORBextractorRight 作为右目特征点提取器
if(sensor==System::STEREO)
mpORBextractorRight = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
// 在单目初始化的时候,会用 mpIniORBextractor 来作为特征点提取器
if(sensor==System::MONOCULAR)
mpIniORBextractor = new ORBextractor(2*nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
mono_tum.cc
为例,送入单张图片及其时间戳进入单目跟踪器接口:SLAM.TrackMonocular(im,tframe)
TrackMonocular()
函数中会检查模式:实时跟踪模式、定位模式、重置等;Tracking::GrabImageMonocular()
函数。Tracking::GrabImageMonocular()
函数
Track()
开始跟踪。enum eTrackingState{
SYSTEM_NOT_READY=-1, // 系统没有准备好的状态,一般就是在启动后加载配置文件和词典文件时候的状态
NO_IMAGES_YET=0, // 当前无图像,图像复位过、或者第一次运行
NOT_INITIALIZED=1, // 有图像但是没有完成初始化
OK=2, // 正常时候的工作状态
LOST=3 // 系统已经跟丢了的状态
};
//跟踪状态
eTrackingState mState;
Tracking::MonocularInitialization()
(需要两帧);Tracking::StereoInitialization()
(由于具有深度信息,直接生成MapPoints)。mbOnlyTracking = false
CheckReplacedInLastFrame()
TrackReferenceKeyFrame()
TrackWithMotionModel()
TrackReferenceKeyFrame()
Relocalization()
mbOnlyTracking = true
mState==LOST
,只能进行重定位:bOK = Relocalization();
;mbVO=false
bOK = TrackWithMotionModel();
bOK = TrackReferenceKeyFrame();
bOK = TrackWithMotionModel();
TrackLocalMap()
bool Tracking::NeedNewKeyFrame()
;
MapPoints
地图点比例比较少;void Tracking::CreateNewKeyFrame()
。在 Pangolin 可视化界面可以选择两种工作模式
mbOnlyTracking = false
mbOnlyTracking = true
跟踪线程用了三种模式进行跟踪, 分别是
前面三种跟踪模型都是为了获取相机位姿一个粗略的初值,后面会通过跟踪局部地图 TrackLocalMap 对位姿进行 Bundle Adjustment (捆集调整),进一步优化位姿。
一旦我们通过上面三种模型获取了初始的相机位姿和初始的特征匹配,就可以将完整的地图投影到当前帧中去搜索更多的匹配。但是投影完整的地图,在 large scale 的场景中是很耗计算而且也没有必要的,因此,这里使用了局部地图 LocalMap 来进行投影匹配。
这部分其实是在进入 Track() 之前进行的,最主要的是进行 ORB 特征提取。
mpORBextractorLeft
作为特征点提取器,在单目初始化的时候,会用 mpIniORBextractor
来作为特征点提取器,两者的区别是后者比前者最多提出的点数多一倍。// tracking过程都会用到 mpORBextractorLeft 作为特征点提取器
mpORBextractorLeft = new ORBextractor( nFeatures, /* 每一帧提取的特征点数 1000 */
fScaleFactor, /* 图像建立金字塔时的变化尺度 1.2 */
nLevels, /* 尺度金字塔的层数 8 */
fIniThFAST, /* 提取fast特征点的默认阈值 20 */
fMinThFAST); /* 如果默认阈值提取不出足够fast特征点,则使用最小阈值 8 */
// 如果是双目,tracking 过程中还会用用到 mpORBextractorRight 作为右目特征点提取器
if(sensor==System::STEREO)
mpORBextractorRight = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
// 在单目初始化的时候,会用 mpIniORBextractor 来作为特征点提取器
if(sensor==System::MONOCULAR)
mpIniORBextractor = new ORBextractor(2*nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
ORBextractor::ORBextractor()
构造函数ORBextractor.cc
中,传入每一帧提取的特征点数量 nFeatures(1000),高斯金字塔每层之间的缩放尺度 fScaleFactor(1.2),高斯金字塔的层数 nLevels(8),Fast 角点提取时的阈值 fIniThFAST(20)和 fMinThFAST(8)。
mvScaleFactor
中,同时计算了其平方 mvLevelSigma2
,其倒数 mvInvScaleFactor
及其平方的倒数 mvInvLevelSigma2
;for(int i = 1; i < nlevels; i++)
{
// 累乘计算得到缩放系数
mvScaleFactor[i] = mvScaleFactor[i-1]*scaleFactor;
// 每层图像相对于初始图像缩放因子的平方.
mvLevelSigma2[i] = mvScaleFactor[i]*mvScaleFactor[i];
}
std::vector mnFeaturesPerLevel
中;
nfeatures×(1-1/scaleFactor)/(1-(1/scaleFactor)^nlevels)
,然后下一层是上一层点数的 1/scaleFactor
倍,以此类推,最后一层兜底;// STEP 将每层的特征点数量进行均匀控制
float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));
// STEP 开始逐层计算要分配的特征点个数,顶层图像除外(看循环后面)
for( int level = 0; level < nlevels-1; level++ )
{
// 分配 cvRound : 返回个参数最接近的整数值
mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
// 累计
sumFeatures += mnFeaturesPerLevel[level];
// 乘缩放系数
nDesiredFeaturesPerScale *= factor;
}
std::vector pattern
,用于后面计算描述子的随机采样点集合;std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
Frame::Frame() 函数传入图像,时间戳,特征点提取器,字典,相机内参矩阵等参数来构造图像帧。首先把要构造金字塔的相关参数给 Frame 类中的跟金字塔相关的元素,然后提取 ORB 特征。(以下为单目帧构造过程)
Frame::ExtractORB(int flag, const cv::Mat &im)
进行 ORB 特征提取,这一步实际上调用了重载函数操作符 ORBextractor::operator()
;(*mpORBextractorLeft)(im, // 待提取特征点的图像
cv::Mat(), // TODO
mvKeys, // 输出变量,用于保存提取后的特征点
mDescriptors);// 输出变量,用于保存特征点的描述子
ORBextractor::ComputePyramid(cv::Mat image)
mvImagePyramid[level]
存储金字塔第 level 层的图像,它是用 resize()
函数得到大小为 level-1
层图像的 scale
倍的线性插值后的图像;copyMakeBorder()
函数来做边界填充。ORBextractor::ComputeKeyPointsOctTree(allKeypoints)
FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), // 待检测的图像,这里就是当前遍历到的【图像块】
vKeysCell, // 存储角点位置的容器
iniThFAST, // 检测阈值
true); // 使能非极大值抑制
ORBextractor::DistributeOctTree()
中进行关键点剔除和平分配
const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));
const float hX = static_cast<float>(maxX-minX)/nIni;
for(size_t i=0;i<vToDistributeKeys.size();i++)
{
// 获取这个关键点对象
const cv::KeyPoint &kp = vToDistributeKeys[i];
// 按点的横轴位置,分配给属于那个图像区域的提取器节点(最初的提取器节点)
vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
}
computeOrientation()
,具体方向计算在 IC_Angle()
函数中
/* @param[in] image 要进行操作的原图像(块)
* @param[in] pt 要计算特征点方向的特征点的坐标
* @param[in] u_max 图像块的每一行的u轴坐标边界(1/4)
* @return float 角度,弧度制
*/
static float IC_Angle( const Mat& image,
Point2f pt,
const vector<int> & u_max)
computeDescriptors()
函数中调用 computeOrbDescriptor()
函数具体实现/**
* @brief 计算ORB特征点的描述子
* @param[in] kpt 特征点对象
* @param[in] img 提取出特征点的图像
* @param[in] pattern 随机采样点集
* @param[out] desc 用作输出变量,保存计算好的描述子,长度为32*8bit
*/
static void computeOrbDescriptor(const KeyPoint& kpt, //特征点对象
const Mat& img, //提取出特征点的图像
const Point* pattern, //随机采样点集
uchar* desc) //用作输出变量,保存计算好的描述子
Frame::UndistortKeyPoints()
;
cv::undistortPoints
进行畸变矫正// 初始化存储地图点句柄的vector
mvpMapPoints = vector<MapPoint*>(N,static_cast<MapPoint*>(NULL));
// 开始认为默认的地图点均为inlier
mvbOutlier = vector<bool>(N,false);
Frame::AssignFeaturesToGrid()
;
std::vector mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]
空间存储的是每个图像网格内特征点的 id;const cv::KeyPoint &kp = mvKeysUn[i];
Frame::PosInGrid()
找到该特征点所处的网格,输出为指定的图像特征点所在的图像网格的横纵 id(其实就是图像网格的坐标)if(PosInGrid(kp,nGridPosX,nGridPosY))
mGrid[nGridPosX][nGridPosY].push_back(i);
在前面构造完 Frame 图像帧之后即进入到 Track() 函数,开始真正开始跟踪线程,第一步就是判断是否进行了初始化,分为单目初始化和双目初始化的情况。
单目初始化通过并行地计算基础矩阵 F 和单应矩阵 H ,恢复出最开始两帧的匹配、相机初始位姿,三角化得到 MapPoints 的深度,获得初始化点云地图。
同时计算两个模型:
用于平面场景的单应性矩阵 H(4对 3d-2d点对,线性方程组,奇异值分解)
用于非平面场景的基础矩阵 F(8对 3d-2d点对,线性方程组,奇异值分解)
mvbPrevMatched
用于存储第一帧中的所有特征点;mvIniMatches
表示两帧之间的匹配标志,先填充为 -1 ,也就是均没有匹配。mCurrentFrame.mvKeys
。ORBmatcher::SearchForInitialization()
函数进行金字塔分层块匹配搜索匹配点对,返回匹配的数目;// 创建特征匹配器.
ORBmatcher matcher( 0.9, true); // 第一个参数:最佳匹配与次佳匹配的比值,默认为 0.6;第二个参数:是否检查特征点的方向.
// 针对单目初始化的时候,进行特征点的匹配
int nmatches = matcher.SearchForInitialization( mInitialFrame, mCurrentFrame, // 初始化时的参考帧和当前帧
mvbPrevMatched, // 在初始化参考帧中提取得到的特征点
mvIniMatches, // 匹配标志
100); // 搜索窗口的大小
ORBmatcher::DescriptorDistance()
函数比较两帧之间的描述子距离,确保距离小于 ORBmatcher::TH_LOW = 50;Initializer::Initialize()
并行计算 H 模型或 F 模型进行单目初始化,得到两帧间相对运动、初始MapPointsmpInitializer->Initialize( mCurrentFrame, // 当前帧
mvIniMatches, // 当前帧和参考帧的特征点的匹配标志
Rcw, tcw, // 初始化得到的相机的位姿
mvIniP3D, // 进行三角化得到的空间点集合
vbTriangulated)) // 以及对应于mvIniMatches来讲,其中哪些点被三角化了
mvIniMatches
存储匹配标志,将标志 >= 0 的点索引关系保存到 mvMatches12if(vMatches12[i]>=0)
{
mvMatches12.push_back(make_pair(i,vMatches12[i]));
mvbMatched1[i]=true;
}
Initializer::mMaxIterations
组,其中 mMaxIterations 是最大的 RANSAC迭代次数,在初始化初始器的时候赋值为 200;
mvSets = vector< vector<size_t> >( mMaxIterations, // 最大的RANSAC迭代次数 200
vector<size_t>(8,0)); //
// 计算 homography 矩阵并打分.
thread threadH( &Initializer::FindHomography, // 计算单应矩阵的函数
this, //NOTE 由于主函数为类的成员函数,所以第一个参数就应该是当前对象的this指针
ref(vbMatchesInliersH), //输出,特征点对的 Inlier 标记
ref(SH), //输出,计算的单应矩阵的 RANSAC 评分
ref(H)); //输出,计算的单应矩阵结果
// 计算 fundamental 矩阵并打分.
thread threadF(&Initializer::FindFundamental,this,ref(vbMatchesInliersF), ref(SF), ref(F));
Initializer::FindHomography()
Initializer::Normalize()
函数归一化特征点的尺度,固定场景尺度;Initializer::ComputeH21()
函数八点法计算 homography 矩阵;Initializer::CheckHomography()
函数求取 利用重投影误差为 RANSAC 的结果评分;Initializer::FindFundamental()
Initializer::Normalize()
函数归一化特征点的尺度,固定场景尺度;Initializer::ComputeF21()
函数八点法计算 fundamental 矩阵;Initializer::CheckFundamental()
函数求取 利用重投影误差为 RANSAC 的结果评分;float RH = SH/(SH+SF);
Initializer::ReconstructH()
;Initializer::ReconstructF()
。mvIniMatches
是两帧之间特征点的匹配标志,vbTriangulated
是其对应的三角化标志。for(size_t i=0, iend = mvIniMatches.size(); i<iend;i++)
{
if(mvIniMatches[i]>=0 && !vbTriangulated[i])
{
mvIniMatches[i]=-1;
nmatches--;
}
}
mInitialFrame.SetPose(cv::Mat::eye(4,4,CV_32F));
// 由Rcw和tcw构造Tcw,并赋值给mTcw,mTcw为世界坐标系到该帧的变换矩阵
cv::Mat Tcw = cv::Mat::eye(4,4,CV_32F);
Rcw.copyTo(Tcw.rowRange(0,3).colRange(0,3));
tcw.copyTo(Tcw.rowRange(0,3).col(3));
mCurrentFrame.SetPose(Tcw);
Tracking::CreateInitialMapMonocular()
将三角化得到的点包装成地图点 MapPoints,创建初始地图,使用最小化重投影误差 BA 进行地图优化,优化位姿和地图点;
KeyFrame::KeyFrame()
KeyFrame* pKFini = new KeyFrame(mInitialFrame, mpMap, mpKeyFrameDB);
KeyFrame* pKFcur = new KeyFrame(mCurrentFrame, mpMap, mpKeyFrameDB);
Frame::ComputeBoW()
pKFini->ComputeBoW();
pKFcur->ComputeBoW();
Map::AddKeyFrame(KeyFrame *pKF)
mpMap->AddKeyFrame(pKFini);
mpMap->AddKeyFrame(pKFcur);
MapPoint::MapPoint()
MapPoint* pMP = new MapPoint(worldPos, // 3D 点的世界坐标.
pKFcur, // 对应的关键帧.
mpMap); // 地图.
KeyFrame::AddMapPoint(MapPoint *pMP, const size_t &idx)
pKFini->AddMapPoint(pMP,i); // 第一个参数是地图点,第二个参数是地图点在关键帧中的索引.
pKFcur->AddMapPoint(pMP,mvIniMatches[i]);
MapPoint::AddObservation(KeyFrame* pKF, size_t idx)
pMP->AddObservation(pKFini,i);
pMP->AddObservation(pKFcur,mvIniMatches[i]);
MapPoint::ComputeDistinctiveDescriptors()
MapPoint::UpdateNormalAndDepth()
AddMapPoint(MapPoint *pMP)
mpMap->AddMapPoint(pMP);
KeyFrame::UpdateConnections()
pKFini->UpdateConnections();
pKFcur->UpdateConnections();
Optimizer::GlobalBundleAdjustemnt()
双目相机通过视差获取深度,RGB-D 相机直接获取深度信息,得到 3D 点,创建地图点并初始化地图。
mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F));
KeyFrame::KeyFrame()
完成关键帧对象的初始化,包括设置关键帧的 ID,位姿,将普通帧的格点关键点数量(加速匹配)统计赋值给关键帧(加速匹配)KeyFrame* pKFini = new KeyFrame(mCurrentFrame, mpMap, mpKeyFrameDB);
Map::AddKeyFrame(KeyFrame *pKF)
mpMap->AddKeyFrame(pKFini);
float z = mCurrentFrame.mvDepth[i]
为正(RGB-D 相机直接获取,双目在构造帧时根据视差计算),然后通过反投影 KeyFrame::UnprojectStereo()
得到该特征点世界坐标系的 3D 坐标;MapPoint::MapPoint()
MapPoint* pNewMP = new MapPoint(x3D,pKFini,mpMap);
AddMapPoint(MapPoint *pMP)
;MapPoint::AddObservation(KeyFrame* pKF, size_t idx)
pKFini->AddMapPoint(pNewMP,i);
mCurrentFrame.mvpMapPoints[i]=pNewMP;
mpLocalMapper->InsertKeyFrame(pKFini);
// 当前帧变上一帧(变为上一个普通帧和关键帧).
mLastFrame = Frame(mCurrentFrame);
mnLastKeyFrameId = mCurrentFrame.mnId;
mpLastKeyFrame = pKFini;
// 添加到局部地图帧集合.
mvpLocalKeyFrames.push_back(pKFini);
// 局部地图中添加所有特征点.
mvpLocalMapPoints = mpMap->GetAllMapPoints();
// 更新参考帧.
mpReferenceKF = pKFini;
mCurrentFrame.mpReferenceKF = pKFini;
// 把当前(最新的)局部 MapPoints 作为地图参考地图点 ReferenceMapPoints
// ReferenceMapPoints 是 DrawMapPoints 函数画图的时候用的
mpMap->SetReferenceMapPoints(mvpLocalMapPoints);
// 地图关键帧
mpMap->mvpKeyFrameOrigins.push_back(pKFini);
// 更新可视化线程地图绘制器.
mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw);
// 更新追踪状态.
mState = OK;
Tracking::CheckReplacedInLastFrame()
函数检查替换情况,函数内再调用 MapPoint* MapPoint::GetReplaced()
函数返回替换的地图点 MapPoint* mpReplaced
MapPoint::Replace(MapPoint* pMP)
局部线程可能会对地图点进行替换。if(mVelocity.empty() || mCurrentFrame.mnId < mnLastRelocFrameId+2)
{
bOK = TrackReferenceKeyFrame();
}
bool Tracking::TrackReferenceKeyFrame()
Frame::ComputeBoW()
(ComputeBoW() 在 Frame 类和 KeyFrame 类中都有)
ComputeBoW()
函数的思想
mBowVec
来表示,词袋向量是一个 map ,元素是视觉词汇和权重;mFeatVec
是用来储存该图像生成 BoW 向量时曾经到达过的第 m 层上节点的编号,以及路过这个节点的特征的编号,意义在于当对两幅图像做涉及到特征点的匹配计算时,可以利用“属于同一单词索引的特征更有可能匹配”的设定规则来加速匹配;正向索引实际上也是一个 map, 元素是节点 ID 和路过这个节点的特征的编号的 vector。DBoW2::BowVector mBowVec
为空时,将当前帧以 opencv 存储的 Mat 类型描述子转换为 std::vectorcv::Mat 类型的向量格式 Converter::toDescriptorVector
vector<cv::Mat> vCurrentDesc = Converter::toDescriptorVector(mDescriptors);
for (int j = 0;j < Descriptors.rows;j++)
transform
函数mpORBvocabulary->transform( vCurrentDesc, // 当前的描述子vector
mBowVec, // 输出,词袋向量
mFeatVec, // 输出,保存有特征点的正向索引 vector
4); // 计算正向索引时,储存到达第四层的节点编号
ORBmatcher::SearchByBoW()
int nmatches = matcher.SearchByBoW( mpReferenceKF, // 参考关键帧
mCurrentFrame, // 当前帧
vpMapPointMatches); // 存储匹配关系
vpMapPointMatches
用于保存当前帧 F 中关键点匹配到的地图点 MapPoints,NULL表示未匹配;ORBmatcher matcher(0.7,true);
,初始化过程需要传入两个参数, 一个是一个阈值, 表示匹配距离最短的距离小于次短距离的 70% ; 另一个是表示特征匹配是否检测特征点的方向是否一致;KFit->first == Fit->first
;MapPoint* pMP = vpMapPointsKF[realIdxKF]; // 取出 KF 中该特征对应的MapPoint
// 剔除
if(!pMP)
continue;
if(pMP->isBad())
continue;
const cv::Mat &dKF= pKF->mDescriptors.row(realIdxKF); // 取出 KF 中该特征对应的描述子
const cv::Mat &dF = F.mDescriptors.row(realIdxF);
ORBmatcher::DescriptorDistance()
,保存最小的、次小的距离,和最小距离对应的 F 特征点的 IDconst int dist = DescriptorDistance(dKF,dF);
vpMapPointMatches
,用于后面向 F 添加地图点;
lower_bound()
使二者保持同步;lower_bound()
在 first 和 last 中的前闭后开区间进行二分查找,返回大于或等于 val 的第一个元素位置,如果所有元素都小于 val,则返回 last 的位置,且 last 的位置是越界的。Optimizer::PoseOptimization(&mCurrentFrame)
。// 如果对应到的某个特征点是外点
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++; // 内点中有观测帧的地图点数量
在 SLAM 模式下,如果不是没有运动速度或刚完成重定位则会优先尝试恒速运动模型,当匹配的特征点较少时再选择关键帧模式;这个模型是假设物体处于匀速运动,例如匀速运动的汽车、机器人、行人等,就可以用上一帧的位姿和速度来估计当前帧的位姿,恒速运动模型实现函数为 Tracking::TrackWithMotionModel()
,匹配是通过投影来与上一帧看到的地图点匹配,使用的是 matcher.SearchByProjection()
。
ORBmatcher matcher(0.9,true);
;Tracking::UpdateLastFrame()
KeyFrame* pRef = mLastFrame.mpReferenceKF;// 上一帧的参考帧.
Trw = pRef->GetPose();// Trw 上一帧的参考帧的位姿.
mLastFrame.mpReferenceKF
到上一帧 mLastFrame
的变换 Tlr 存储为 mlRelativeFramePoses
的最后一个元素:cv::Mat Tlr = mlRelativeFramePoses.back();
mLastFrame.SetPose(Tlr*pRef->GetPose()); // Tlr*Trw = Tlw l:last r:reference w:world
vector > vDepthIdx;
,其中第一个元素是某个点的深度,第二个元素是对应的特征点 id;sort(vDepthIdx.begin(),vDepthIdx.end());
;mlpTemporalPoints.push_back(pNewMP);
。mCurrentFrame.SetPose(mVelocity * mLastFrame.mTcw);
,同时清空当前帧的地图点;
mLastFrame.mTcw
由步骤二得到;mVelocity = mCurrentFrame.mTcw * LastTwc;
也就是上一帧和上一帧的参考帧之间的相对运动 Tcl。ORBmatcher::SearchByProjection()
根据上一帧特征点对应的3D点投影的位置和网格搜索缩小特征点匹配范围
// 获取上一帧地图点的世界坐标和相机坐标.
cv::Mat x3Dw = pMP->GetWorldPos();
cv::Mat x3Dc = Rcw*x3Dw+tcw;
// 上一帧特征点的 3D 坐标
const float xc = x3Dc.at<float>(0);
const float yc = x3Dc.at<float>(1);
const float invzc = 1.0/x3Dc.at<float>(2);
// 利用当前帧的位姿将其投影到当前帧.
float u = CurrentFrame.fx * xc * invzc + CurrentFrame.cx;
float v = CurrentFrame.fy * yc * invzc + CurrentFrame.cy;
const bool bForward = tlc.at<float>(2)>CurrentFrame.mb && !bMono; // 非单目情况,如果Z大于基线,则表示前进
const bool bBackward = -tlc.at<float>(2)>CurrentFrame.mb && !bMono; // 非单目情况,如果Z小于基线,则表示前进
Frame::GetFeaturesInArea()
函数获取这个区域网格中的地图点集合 vector vIndices2;
// BRIEF 找到在 以x,y为中心,边长为2r的方形内且在[minLevel, maxLevel]的特征点
vector<size_t> Frame::GetFeaturesInArea(const float &x,
const float &y,
const float &r,
const int minLevel,
const int maxLevel) const
ORBmatcher::DescriptorDistance()
计算描述子距离。Optimizer::PoseOptimization(Frame *pFrame)
,仅优化单个普通帧的位姿,地图点不优化。 假如恒速运动模型跟踪失败,与相邻关键帧匹配也失败,则认为当前帧已丢失,需要进行重定位,通过词袋向量搜索关键帧数据库中与之对应的关键帧进行匹配跟踪。重定位实现函数在 Tracking::Relocalization()
中。
Frame::ComputeBoW()
,参考 3.1 节跟踪参考帧模型的步骤一;list lKFsSharingWords
;minCommonWords
;minCommonWords
且单词匹配度大于 minScore 的关键帧,将匹配度和关键帧存入 list > lScoreAndMatch
;bestAccScore
,并以此此得分的 0.75 倍作为阈值minScoreToRetain
;
ORBmatcher matcher(0.75,true)
;SearchByBoW(pKF,mCurrentFrame,vvpMapPointMatches[i])
,参考 3.1 节的步骤二 。PnPsolver* pSolver = new PnPsolver(mCurrentFrame,vvpMapPointMatches[i]);
PnPsolver::iterate()
函数中进行,返回当前帧位姿;Optimizer::PoseOptimization()
;ORBmatcher::SearchByProjection
中,具体参考 3.2 节的步骤四。 帧间位姿估计的三种模型是为了获取当前帧的一个位姿初值,在前面三种模式每次跟踪成功之后还需要跟踪局部地图,进行 BA 优化。实现函数在 Tracking::TrackLocalMap()
中。
Tracking::UpdateLocalMap()
,更新局部关键帧 mvpLocalKeyFrames 和局部地图点 mvpLocalMapPoints;
Map::SetReferenceMapPoints()
mpMap->SetReferenceMapPoints(mvpLocalMapPoints);
Tracking::UpdateLocalKeyFrames()
,生成对应当前帧的局部地图(小图)
Tracking::UpdateLocalPoints()
,所有局部关键帧包含的地图点构成局部地图点;
Tracking::SearchLocalPoints()
中
matcher.SearchByProjection(mCurrentFrame,mvpLocalMapPoints,th);
Optimizer::PoseOptimization()
; 在跟踪成功之后(三种跟踪模式和地图跟踪成功之后)判断是否需要创建关键帧,判断函数在 Tracking::NeedNewKeyFrame()
中
const bool c1a = mCurrentFrame.mnId >= mnLastKeyFrameId+mMaxFrames;
LocalMapping::AcceptKeyFrames()
bool bLocalMappingIdle = mpLocalMapper->AcceptKeyFrames();
const bool c1b = (mCurrentFrame.mnId>=mnLastKeyFrameId+mMinFrames && bLocalMappingIdle);
// 跟踪要跪的节奏,0.25和0.3是一个比较低的阈值
const bool c1c = mSensor!=System::MONOCULAR && //只有在双目的时候才成立
(mnMatchesInliers<nRefMatches*0.25 || //和地图点匹配的数目非常少
ratioMap<0.3f) ; //地图点跟踪成功的比例非常小,要挂了
// 阈值比c1c要高,与之前参考帧(最近的一个关键帧)重复度不是太高
const bool c2 = ((mnMatchesInliers<nRefMatches*thRefRatio || // 总的来说,还是参考关键帧观测到的地图点的数目太少,少于给定的阈值
ratioMap<thMapRatio) && // 追踪到的地图点的数目比例太少,少于阈值
mnMatchesInliers>15); //匹配到的内点太少
(c1a || c1b || c1c) && c2
当上一步返回 true 时,说明可以创建新的关键帧,创建关键帧具体在 Tracking::CreateNewKeyFrame()
中实现。
KeyFrame* pKF = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB);
// 在UpdateLocalKeyFrames函数中会将与当前关键帧共视程度最高的关键帧设定为当前帧的参考关键帧
mpReferenceKF = pKF;
mCurrentFrame.mpReferenceKF = pKF;
sort(vDepthIdx.begin(),vDepthIdx.end());
pNewMP->AddObservation(pKF,i);
pKF->AddMapPoint(pNewMP,i);
pNewMP->ComputeDistinctiveDescriptors();
pNewMP->UpdateNormalAndDepth();
mpMap->AddMapPoint(pNewMP);
mlNewKeyFrames
中供局部建图线程处理 LocalMapping::InsertKeyFrame(KeyFrame *pKF)
void LocalMapping::InsertKeyFrame(KeyFrame *pKF)
{
unique_lock<mutex> lock(mMutexNewKFs);
// 将关键帧插入到列表中
mlNewKeyFrames.push_back(pKF);
mbAbortBA=true;
}
2019.04.27
[email protected]