【ORB-SLAM2源码梳理2】进入Tracking线程(Tracking.cc)


前言

继续!


一、Tracking线程

在这里插入图片描述
从框架图可看出,Tracking线程
输入:图像帧(Frame)
输出:关键帧(KeyFrame)

对输入的图像帧进行以下四个步骤的操作:
① 输入预处理,即ORB特征提取;
② 对上一帧进行初始化位姿估计或重定位;
③ 跟踪局部地图,为了实现更精确的跟踪效果;
④ 决策是否生成新的关键帧;


二、Tracking构造函数

System.ccSystem构造函数中的初始化Tracking线程mpTracker = new Tracking(),进入Tracking.ccTracking构造函数。

主要作用:
① 从配置文件中读取相机内参、畸变系数、图片的颜色序列、图像金字塔的参数;
② 创建特征提取器,为后续特征提取做准备

Tracking::Tracking(
    System *pSys,                       //创建系统,指针
    ORBVocabulary* pVoc,                //BOW字典,指针
    FrameDrawer *pFrameDrawer,          //帧绘制器,指针
    MapDrawer *pMapDrawer,              //地图点绘制器,指针
    Map *pMap,                          //地图句柄,指针
    KeyFrameDatabase* pKFDB,            //关键帧产生的词袋数据库,指针
    const string &strSettingPath,       //配置文件路径,string类
    const int sensor):                  //传感器类型
        mState(NO_IMAGES_YET),                              // 当前系统还没有准备好
        mSensor(sensor),                                    // 传感器类型
        mbOnlyTracking(false),                              // true为纯定位模式,false为SLAM模式
        mbVO(false),                                        // 当处于纯跟踪模式时,才会存在这个变量。
        													// 此变量表示了当前跟踪状态的好坏,false为正常,true为没有匹配到地图点
        mpORBVocabulary(pVoc),                              // ORB特征字典导入BoW词袋模型中
        mpKeyFrameDB(pKFDB),                                // 当前系统运行时,关键帧产生的词袋数据库
        mpInitializer(static_cast<Initializer*>(NULL)),     // 单目初始化器(双目、RGBD模式不会有这个),暂时给地图初始化器设置为空指针
        mpSystem(pSys),                                     // 指向系统的指针
        mpViewer(NULL),                                     // 注意可视化的查看器是可选的,因为ORB-SLAM2最后是被编译成为一个库,
                                                            // 所以拿过来用的时候也应该有权力说我不要可视化界面(何况可视化界面也要占用不少的CPU资源)
        mpFrameDrawer(pFrameDrawer),                        // 帧绘制器句柄
        mpMapDrawer(pMapDrawer),                            // 地图绘制器句柄
        mpMap(pMap),                                        // 全局地图句柄
        mnLastRelocFrameId(0)                               // 恢复为0,没有进行这个过程时的默认值

step1:从配置文件strSettingPath中以只读的方式加载相机参数(内参、畸变系数、基线长度、帧数):

cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); 

step2:加载ORB特征点相关参数,并新建特征点提取器

// 构造特征提取器,重点!!!
    mpORBextractorLeft = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
// 若为双目,还有右特征点提取器
    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);        

三、Tracking.cc中的其他关键代码

GrabImageMonocular()函数

注:首次出现于System.cc中的cv::Mat System::TrackMonocular(const cv::Mat &im, const double &timestamp);

cv::Mat Tcw = mpTracker->GrabImageMonocular(im,timestamp);

功能:
① 将图像转为mImGray(灰度图)并初始化mCurrentFrame(初始化当前帧);
② 进行Tracking过程,输出世界坐标系到该帧相机坐标系的变换矩阵。

步骤:
① 彩色图转灰度图;
② 构造帧Frame;
③ 跟踪Track。

cv::Mat Tracking::GrabImageMonocular(const cv::Mat &im, const double &timestamp)
{
	...// 用opencv函数转换灰度图
	if(mState==NOT_INITIALIZED || mState==NO_IMAGES_YET)
        mCurrentFrame = Frame(mImGray,timestamp,mpIniORBextractor,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
    else
        mCurrentFrame = Frame(mImGray,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
	...// 跟踪、返回当前帧从世界坐标系到相机坐标系下的变换矩阵
}

源码解释:
判断当前帧是否进行了初始化,没有初始化成功的前一个状态为NO_IMAGES_YET,调用Tracking构造函数时赋给mState的值就是NO_IMAGES_YET;若没有初始化,则执行else语句。
两者的区别:ORB特征提取器使用的不同,未初始化的帧使用mpIniORBextractor,会提取2倍指定数目的特征点。


总结

按照图像帧的处理流程撰写文章,GrabImageMonocular()中的构造帧Frame和跟踪Track()会在后续的系列文章中进行梳理。

未完待续!!!

  • 1
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 2
    评论
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

Jay_z在造梦

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值