先要拿大名鼎鼎的ORB-SLAM系统框图镇楼,看着这张图能够完美的串起来整个流程。
ORB-SLAM分三个线程,分别是Tracking、LocalMapping和LoopClosing。
(1)Tracking:在主线程上,输入视频流,输出相机位姿并跟踪局部地图。提取ORB特征子,根据上一帧进行位姿估计或全局重定位,然后跟踪局部地图优化位姿,确定新的关键帧。
(2)LocalMapping:维护优化局部地图。输入关键帧,输出修正的关键帧和地图点。插入关键帧,生成新的地图点,使用BA优化,去除冗余的关键帧
(3)LoopClosing:闭环检测和闭环矫正。BOW检测,再用Sim3计算相似变换;闭环融合与优化Essential Graph的图优化。
#ifndef SYSTEM_H
#define SYSTEM_H
#include<string>
#include<thread>
#include<opencv2/core/core.hpp>
#include "Tracking.h"
#include "FrameDrawer.h"
#include "MapDrawer.h"
#include "Map.h"
#include "LocalMapping.h"
#include "LoopClosing.h"
#include "KeyFrameDatabase.h"
#include "ORBVocabulary.h"
#include "Viewer.h"
namespace ORB_SLAM2
{
class Viewer;
class FrameDrawer;
class Map;
class Tracking;
class LocalMapping;
class LoopClosing;
class System
{
public:
// 三种传感器选择
enum eSensor{
MONOCULAR=0,
STEREO=1,
RGBD=2
};
//成员函数
public:
// 声明
System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, const bool bUseViewer = true);
// Tracking函数:输出相机位姿
cv::Mat TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double ×tamp);
cv::Mat TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double ×tamp);
cv::Mat TrackMonocular(const cv::Mat &im, const double ×tamp);
// 激活定位模块;停止Local Mapping,只相机追踪???
void ActivateLocalizationMode();
// 失效定位模块;恢复Local Mapping,再次执行SLAM???
void DeactivateLocalizationMode();
// 清空地图,重启系统
void Reset();
// 保存轨迹之前执行
void Shutdown();
// 保存相机轨迹 Only stereo and RGB-D.
// Call first Shutdown()
// See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset
void SaveTrajectoryTUM(const string &filename);
// See format details at: http://www.cvlibs.net/datasets/kitti/eval_odometry.php
void SaveTrajectoryKITTI(const string &filename);
// 保存关键帧位姿
// Call first Shutdown()
// See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset
void SaveKeyFrameTrajectoryTUM(const string &filename);
//成员变量
private:
// Input sensor
eSensor mSensor;
// ORB词汇表用于场景识别和特征匹配
ORBVocabulary* mpVocabulary;
// 关键帧数据库用于位置识别 (重定位和回环检测).
KeyFrameDatabase* mpKeyFrameDatabase;
// 存储关键帧和地图特征子
Map* mpMap;
// Tracker. 接受帧计算相机位姿
// 决定何时插入新的关键帧,创建新的地图特征子
// 重定位
Tracking* mpTracker;
// Local Mapper.管理本地地图,执行BA
LocalMapping* mpLocalMapper;
// Loop Closer. 搜索每个新的关键帧的循环
LoopClosing* mpLoopCloser;
// Pangolin.绘制地图和当前相机位姿
Viewer* mpViewer;
// 画图用的
FrameDrawer* mpFrameDrawer;
MapDrawer* mpMapDrawer;
// 3个线程: Local Mapping, Loop Closing, Viewer.
// Tracking线程在System主程序线程中
std::thread* mptLocalMapping;
std::thread* mptLoopClosing;
std::thread* mptViewer;
// 重置Flag???
std::mutex mMutexReset;
bool mbReset;
//更改模型flags
std::mutex mMutexMode;
bool mbActivateLocalizationMode;
bool mbDeactivateLocalizationMode;
};
}// namespace ORB_SLAM
#endif // SYSTEM_H
#include "System.h"
#include "Converter.h"
#include <thread>
#include <pangolin/pangolin.h>
#include <iostream>