2021SC@SDUSC
1.算法框架
如果直接看源码纠缠在细节上,会缺乏对整体的把握,所以先通过下图对ORB-SLAM3的算法框架结构做到一目了然!
2.数据关联
为什么SLAM3的精度这么高?
可以从它数据关联角度去解释:
- 短期数据关联。仅仅和最近几秒内获取的地图元素进行匹配。这是大多数视觉里程计使用的唯一数据关联类型,这种方法存在的问题是:一旦地图元素从视野中消失,就会被丢弃,即使回到原来的地方,也会造成持续的估计漂移。对应ORB-SLAM里的跟踪。
- 中期数据关联。匹配距离相机近并且累积漂移较小的地图元素。与短期观测相比,这些信息可以一并加入BA优化,当相机移动到已经建好图的区域时,可以达到零漂移。这是该系统与带闭环检测的视觉里程计相比,精度更高的关键所在。对应ORB-SLAM里的局部建图。
- 长期数据关联。使用位置识别技术将观测与之前访问过的区域中的元素匹配,不管是在闭环检测中的累积漂移,还是跟踪丢失、重定位的情况下都可以成功匹配。长期匹配允许使用位姿图优化来重置漂移和矫正闭环。这是保证中、大型闭环场景中SLAM局部较高精度的关键。对应ORB-SLAM里用词袋进行闭环和重定位。
- 多地图数据关联。可以使用之前已经建立的多块地图来实现地图中的匹配和BA优化。
ORB-SLAM3充分使用了短期、中期、长期的数据关联,可以达到在已经建图区域的零漂移。
3.代码命名规范(便于理解)
我们有必要先了解一下在ORB-SLAM2中变量的命名规则,这对我们学习代码非常有用。
以小写字母m(member的首字母)开头的变量表示类的成员变量。比如:
int mSensor;
int mTrackingState;
std::mutex mMutexMode;
对于某些复杂的数据类型,第2个甚至第3个字母也有一定的意义,比如:
mp开头的变量表示指针(pointer)型类成员变量;
Tracking* mpTracker;
LocalMapping* mpLocalMapper;
LoopClosing* mpLoopCloser;
Viewer* mpViewer;
mb开头的变量表示布尔(bool)型类成员变量;
bool mbOnlyTracking;
mv开头的变量表示向量(vector)型类成员变量;
std::vector<int> mvIniLastMatches;
std::vector<cv::Point3f> mvIniP3D;
mpt开头的变量表示指针(pointer)型类成员变量,并且它是一个线程(thread);
std::thread* mptLocalMapping;
std::thread* mptLoopClosing;
std::thread* mptViewer;
ml开头的变量表示列表(list)型类成员变量;
mlp开头的变量表示列表(list)型类成员变量,并且它的元素类型是指针(pointer); mlb开头的变量表示列表(list)型类成员变量,并且它的元素类型是布尔型(bool);
list<double> mlFrameTimes;
list<bool> mlbLost;
list<cv::Mat> mlRelativeFramePoses;
list<KeyFrame*> mlpReferences;
4.KeyFrameDatabase
4.1关键帧数据库
构建关键帧数据库,可以联系链表等常用数据结构的构建过程:创建、增加元素、删除元素、清理。
首先需要明确数据存储的数据类型:以关键帧作为数据库的元素。
这个地方需要理解两个概念:单词(词袋)和关键帧。
单词(词袋):预先构建好的,离线词典(ORBvoc.txt):它是DBoW2作者使用orb特征,使用大量图片训练的结果。
4.2代码分析
根据关键帧的BoW,更新数据库的倒排索引
void KeyFrameDatabase::add(KeyFrame *pKF)
{
unique_lock<mutex> lock(mMutex);
// 为每一个word添加该KeyFrame
for(DBoW2::BowVector::const_iterator vit= pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++)
mvInvertedFile[vit->first].push_back(pKF);
}
关键帧被删除后,更新数据库的倒排索引
void KeyFrameDatabase::erase(KeyFrame* pKF)
{
unique_lock<mutex> lock(mMutex);
// Erase elements in the Inverse File for the entry
// 每一个KeyFrame包含多个words,遍历mvInvertedFile中的这些words,然后在word中删除该KeyFrame
for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++)
{
// List of keyframes that share the word
list<KeyFrame*> &lKFs = mvInvertedFile[vit->first];
for(list<KeyFrame*>::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++)
{
if(pKF==*lit)
{
lKFs.erase(lit);
break;
}
}
}
}
清空关键帧数据库
void KeyFrameDatabase::clear()
{
mvInvertedFile.clear();
mvInvertedFile.resize(mpVoc->size());
}
void KeyFrameDatabase::clearMap(Map* pMap)
{
unique_lock<mutex> lock(mMutex);
// Erase elements in the Inverse File for the entry
for(std::vector<list<KeyFrame*> >::iterator vit=mvInvertedFile.begin(), vend=mvInvertedFile.end(); vit!=vend; vit++)
{
// List of keyframes that share the word
list<KeyFrame*> &lKFs = *vit;
for(list<KeyFrame*>::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend;)
{
KeyFrame* pKFi = *lit;
if(pMap == pKFi->GetMap())
{
lit = lKFs.erase(lit);
// Dont delete the KF because the class Map clean all the KF when it is destroyed
}
else
{
++lit;
}
}
}
}
参考文献
从ORB-SLAM2的源码工程中学习C++编程——关键帧数据库