构造函数
//系统的构造函数,将会启动其他的线程
System::System(const string &strVocFile, //词典文件路径
const string &strSettingsFile, //配置文件路径
const eSensor sensor, //传感器类型
const bool bUseViewer): //是否使用可视化界面
mSensor(sensor), //初始化传感器类型
mpViewer(static_cast<Viewer*>(NULL)), //空。。。对象指针? TODO
mbReset(false), //无复位标志
mbActivateLocalizationMode(false), //没有这个模式转换标志
mbDeactivateLocalizationMode(false) //没有这个模式转换标志
{
}
mSensor是System的成员,并且private里的都是System的私有成员变量
// Output welcome message
cout << endl <<
"ORB-SLAM2 Copyright (C) 2014-2016 Raul Mur-Artal, University of Zaragoza." << endl <<
"This program comes with ABSOLUTELY NO WARRANTY;" << endl <<
"This is free software, and you are welcome to redistribute it" << endl <<
"under certain conditions. See LICENSE.txt." << endl << endl;
// 输出当前传感器类型
cout << "Input sensor was set to: ";
if(mSensor==MONOCULAR)
cout << "Monocular" << endl;
else if(mSensor==STEREO)
cout << "Stereo" << endl;
else if(mSensor==RGBD)
cout << "RGB-D" << endl;
//Check settings file
cv::FileStorage fsSettings(strSettingsFile.c_str(), //将配置文件名转换成为字符串
cv::FileStorage::READ); //只读
//如果打开失败,就输出调试信息
if(!fsSettings.isOpened())
{
cerr << "Failed to open settings file at: " << strSettingsFile << endl;
//然后退出
exit(-1);
}
//Load ORB Vocabulary
cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl;
//建立一个新的ORB字典
mpVocabulary = new ORBVocabulary();
//获取字典加载状态
bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
//如果加载失败,就输出调试信息
if(!bVocLoad)
{
cerr << "Wrong path to vocabulary. " << endl;
cerr << "Falied to open at: " << strVocFile << endl;
//然后退出
exit(-1);
}
//否则则说明加载成功
cout << "Vocabulary loaded!" << endl << endl;
mpVocabulary = new ORBVocabulary(); 是一个指针,
指向ORB字典ORBVocabulary* mpVocabulary;
mpVocabulary->loadFromTextFile,ORBVocabulary这种数据类型有loadFromTextFile方法
//Create KeyFrame Database
mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);
关键帧数据库的指针,这个数据库用于重定位和回环检测
// 构造函数
KeyFrameDatabase::KeyFrameDatabase (const ORBVocabulary &voc):
mpVoc(&voc)
{ // 数据库的主要内容了
mvInvertedFile.resize(voc.size()); // number of words
}
在构造时初始化mpVoc(&voc)表示将 voc
对象的地址赋值给 mpVoc
这个指针变量。这种赋值方式实际上是将某个变量的地址存储到指针中,使得指针可以通过该地址访问该变量。将 voc
对象作为成员变量 mpVoc
的初始值。当然voc就是一个指向 ORBVocabulary
对象的指针
//Create the Map
mpMap = new Map();
//Create Drawers. These are used by the Viewer
//这里的帧绘制器和地图绘制器将会被可视化的Viewer所使用
mpFrameDrawer = new FrameDrawer(mpMap);
mpMapDrawer = new MapDrawer(mpMap, strSettingsFile);
指向地图(数据库)的指针mpMap
//在本主进程中初始化追踪线程
//Initialize the Tracking thread
//(it will live in the main thread of execution, the one that called this constructor)
mpTracker = new Tracking(this, //现在还不是很明白为什么这里还需要一个this指针 TODO
mpVocabulary, //字典
mpFrameDrawer, //帧绘制器
mpMapDrawer, //地图绘制器
mpMap, //地图
mpKeyFrameDatabase, //关键帧地图
strSettingsFile, //设置文件路径
mSensor); //传感器类型iomanip
//初始化局部建图线程并运行
//Initialize the Local Mapping thread and launch
mpLocalMapper = new LocalMapping(mpMap, //指定使iomanip
mSensor==MONOCULAR); // TODO 为什么这个要设置成为MONOCULAR???
//运行这个局部建图线程
mptLocalMapping = new thread(&ORB_SLAM2::LocalMapping::Run, //这个线程会调用的函数
mpLocalMapper); //这个调用函数的参数
通过执行 new thread(&ORB_SLAM2::LocalMapping::Run, mpLocalMapper)
,创建了一个新的线程,并将 ORB_SLAM2::LocalMapping::Run
作为线程的执行函数,mpLocalMapper
作为 Run
函数的参数。这样,每当 mptLocalMapping
线程启动时,就会调用 Run
函数并传入 mpLocalMapper
。通过这种方式,我们可以在另一个线程中并行执行 Run
函数以及关联的操作。&ORB_SLAM2::LocalMapping::Run
表示取得 ORB_SLAM2::LocalMapping::Run
函数的地址。这是因为 std::thread
构造函数需要一个函数指针作为参数,而通过 &
取得函数的地址就可以获得一个函数指针。这样,线程就可以使用这个函数指针来调用 ORB_SLAM2::LocalMapping::Run
函数。
//Initialize the Loop Closing thread and launchiomanip
mpLoopCloser = new LoopClosing(mpMap, //地图
mpKeyFrameDatabase, //关键帧数据库
mpVocabulary, //ORB字典
mSensor!=MONOCULAR); //当前的传感器是否是单目
//创建回环检测线程
mptLoopClosing = new thread(&ORB_SLAM2::LoopClosing::Run, //线程的主函数
mpLoopCloser); //该函数的参数
//Initialize the Viewer thread and launch
if(bUseViewer)
{
//如果指定了,程序的运行过程中需要运行可视化部分
//新建viewer
mpViewer = new Viewer(this, //又是这个
mpFrameDrawer, //帧绘制器
mpMapDrawer, //地图绘制器
mpTracker, //追踪器
strSettingsFile); //配置文件的访问路径
//新建viewer线程
mptViewer = new thread(&Viewer::Run, mpViewer);
//给运动追踪器设置其查看器
mpTracker->SetViewer(mpViewer);
}
线程有,局部建图线程mptLocalMapping、回环检测线程mptLoopClosing、新建viewer线程mptViewer。在 ORB_SLAM2 的实现中,一共有 3 个线程:
-
mptLocalMapping
线程:这是局部建图线程,负责处理新的关键帧,进行局部地图的更新和优化。 -
mptLoopClosing
线程:这是回环检测线程,负责检测回环,并在检测到回环时进行回环优化,从而提高SLAM系统的鲁棒性和精度。 -
mptViewer
线程:这是新建的 Viewer 线程,负责实时地可视化当前的地图和位姿,将地图以三维点云和相机轨迹的形式显示出来。
这三个线程并行运行,分别完成不同的任务,共同构成了整个ORB_SLAM2系统。它们之间通过共享数据来进行信息的传递与交互,从而实现了即时的场景重建和定位。
//Set pointers between threads
//设置进程间的指针
mpTracker->SetLocalMapper(mpLocalMapper);
mpTracker->SetLoopClosing(mpLoopCloser);
mpLocalMapper->SetTracker(mpTracker);
mpLocalMapper->SetLoopCloser(mpLoopCloser);
mpLoopCloser->SetTracker(mpTracker);
mpLoopCloser->SetLocalMapper(mpLocalMapper);
mpTracker
类中的 SetLocalMapper
成员函数通常会将传入的 mpLocalMapper
指针保存在 mpTracker
类的成员变量中。
//设置局部建图器
void Tracking::SetLocalMapper(LocalMapping *pLocalMapper)
{
mpLocalMapper=pLocalMapper;
}