(01)ORB-SLAM2源码无死角解析-(06) 图像金字塔_ORB特征点

讲解关于slam一系列文章汇总链接:史上最全slam从零开始,针对于本栏目讲解的(01)ORB-SLAM2源码无死角解析链接如下(本文内容来自计算机视觉life ORB-SLAM2 课程课件):
(01)ORB-SLAM2源码无死角解析-(00)目录_最新无死角讲解:https://blog.csdn.net/weixin_43013761/article/details/123092196
 
文末正下方中心提供了本人 联系方式, 点击本人照片即可显示 W X → 官方认证 {\color{blue}{文末正下方中心}提供了本人 \color{red} 联系方式,\color{blue}点击本人照片即可显示WX→官方认证} 文末正下方中心提供了本人联系方式,点击本人照片即可显示WX官方认证
 

一、前言

上一节我们说到了 src/Frame.cc 中的 Frame::Frame() 函数,调用了比较重要的两个函数:

    // ORB extraction
	// Step 3 对这个单目图像进行提取特征点, 第一个参数0-左图, 1-右图
    ExtractORB(0,imGray);
    // Step 4 用OpenCV的矫正函数、内参对提取到的特征点进行矫正 
    UndistortKeyPoints();

我们首先对 ExtractORB() 进行讲解,UndistortKeyPoints() 放到后面的章节。进入 ExtractORB 函数,可以看到其实现如下:

void Frame::ExtractORB(int flag, const cv::Mat &im)
{
    // 判断是左图还是右图
    if(flag==0)
        // 左图的话就套使用左图指定的特征点提取器,并将提取结果保存到对应的变量中 
        // 这里使用了仿函数来完成,重载了括号运算符 ORBextractor::operator() 
        (*mpORBextractorLeft)(im,				//待提取特征点的图像
							  cv::Mat(),		//掩摸图像, 实际没有用到
							  mvKeys,			//输出变量,用于保存提取后的特征点
							  mDescriptors);	//输出变量,用于保存特征点的描述子
    else
        // 右图的话就需要使用右图指定的特征点提取器,并将提取结果保存到对应的变量中 
        (*mpORBextractorRight)(im,cv::Mat(),mvKeysRight,mDescriptorsRight);
}

可以看到,其主要是通过 mpORBextractorLeft,或者 mpORBextractorRight 调用函数,通过前面的章节我们可以知道这两个类对象是在 Tracking::Tracking 构造函数中创建的:

    // tracking过程都会用到mpORBextractorLeft作为特征点提取器
    mpORBextractorLeft = new ORBextractor(
        nFeatures,      //参数的含义还是看上面的注释吧
        fScaleFactor,
        nLevels,
        fIniThFAST,
        fMinThFAST);

    // 如果是双目,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,前面的:

        (*mpORBextractorLeft)(im,cv::Mat(),mvKeys,mDescriptors);
        # 或者
        (*mpORBextractorRight)(im,cv::Mat(),mvKeysRight,mDescriptorsRight);

其本质上调用的是 src\ORBextractor.cc 文件中的 ORBextractor::operator() 函数。暂且不论,我们想来了解一下 图像金字塔 与 特征点的相关知识

 

二、图像金字塔

在讨论构造函数 ORBextractor::ORBextractor() 之前,我们先了解一下什么是图像金字塔,这个东西呢,我们不用想得太复杂了,简单的说就是:

	对一张图像进行连续的等比缩放(一般是缩小),把多次缩放之后的图像加上原图,我们统称为图像金字塔

如下图所示:
在这里插入图片描述
其上的 Level 0 表示原图, Level 1 则为 按照缩放因子 f 进行第一次缩放的结果,Level 2 则是在 Level 1 的基础上,按照放因子 f 再次进行缩放之后的结果。这样一次循环叠加,形成了上面的图像金字塔。使用图像金字塔,我们可以提取到图像各个尺寸的关键点,这样增加了算法的鲁棒性。了解图像金字塔之后,我们在来看看fast特征是什么。

 

三、ORB特征点

说到 fast特征 之前,我们先来说说ORB特征,特征点一般具备如下性质(SIFT、SURF、ORB等特征点):

	1、可重复性:即相同的“区域“可以在不同的图像中找到(比如将特征点比作一只猫,在图一和图二中都能找到这只猫)。
	2、可区别性:即不同的”区域“有不同的表达。
	3、高效率:在同一副图像中,特征点的数量应该远小于像素的数量。
	4、本地性:特征仅与一小片图像区域相关。

特征点主要由关键点与描述子两个部分组成:
        关键点: 通常是指该特征点在图像中的位置,有的特征点还具有朝向、大小等信息。
        描述子: 通常是一个向量,按照认为设计的方式,描述了该关键点周围像素的信息。描述子的设计原则是外观相似的特征应该有相似的描述子。

O R B 特征 : \color{red}{ORB特征:} ORB特征:特征也是由关键点和描述子组成。正如其英文全名一样,这种特征使用的特征点是”Oriented FAST“,描述子是”Rotated BRIEF“。其实这两种关键点与描述子都是在ORB特征出现之前就已经存在了,ORB特征的作者将二者进行了一定程度的改进,并将这两者巧妙地结合在一起,得出一种可以快速提取的特征--ORB特征。ORB特征在速度方面相较于SIFT、SURF已经有明显的提升的同时,保持了特征子具有旋转与尺度不变性。

对于 Oriented FAST 关键点与 Rotated BRIEF 描述子,我们在下篇博客进行详细的讲解这篇博客我们先来看看代码。

 

四、代码实现

该篇博客的前言部分我们提到了 Frame::ExtractORB() 函数,本质上调用的是 src\ORBextractor.cc 文件中的 ORBextractor::operator() 函数,在讲解该函数之前,我们先来看看 ORBextractor::ORBextractor() 构造函数,其主要执行了以下流程:

	# ORBextractor.scaleFactor参数默认为1.2  ORBextractor.nLevels默认为8,表示8层金字塔
	1、获取每层金字塔的缩放因子,以及缩放因子的方平(主要用于面积计算),缩放因子来自
	yaml配置文件中的 ORBextractor.scaleFactor 参数。
		(1)mvScaleFactor,mvInvScaleFactor = 每层金字塔缩放因子,缩放因子的倒数
	    (2)mvLevelSigma2,mvInvLevelSigma2 = 每层金字塔缩放因子平方,缩放因子平方的倒数
	
	# ORBextractor.nFeatures: 1000, 表示所有金字塔一共需要提取1000个特征点
	2、mnFeaturesPerLevel:用于存储每层图像金字塔应该提取的特征点数目,其分配方式主要根据	  
	面积进行计算。面积越大,提取的特征数目越多。如果按按面积分配特征点出现多余,未分配的特征
	点,默认分配给最后一层金字塔(最小的那一层)

	
	3、pattern0:其主要和描述子相关,暂时不做详细讲解
	   umax:其主要和描述子相关主要用于记录X的坐标的最大值,暂时不用理会即可

其构造函数的代码注释如下:

//特征点提取器的构造函数

ORBextractor::ORBextractor(int _nfeatures,		//指定要提取的特征点数目
                           float _scaleFactor,	//指定图像金字塔的缩放系数
                           int _nlevels,		//指定图像金字塔的层数
                           int _iniThFAST,		//指定初始的FAST特征点提取参数,可以提取出最明显的角点
                           int _minThFAST):		//如果初始阈值没有检测到角点,降低到这个阈值提取出弱一点的角点
    nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
    iniThFAST(_iniThFAST), minThFAST(_minThFAST)//设置这些参数
{
    //存储每层图像缩放系数的vector调整为符合图层数目的大小
    mvScaleFactor.resize(nlevels);  
    //存储这个sigma^2,其实就是每层图像相对初始图像缩放因子的平方
    mvLevelSigma2.resize(nlevels);
    //对于初始图像,这两个参数都是1
    mvScaleFactor[0]=1.0f;
    mvLevelSigma2[0]=1.0f;
    //然后逐层计算图像金字塔中图像相当于初始图像的缩放系数 
    for(int i=1; i<nlevels; i++)  
    {
        //其实就是这样累乘计算得出来的
        mvScaleFactor[i]=mvScaleFactor[i-1]*scaleFactor;
        //原来这里的sigma^2就是每层图像相对于初始图像缩放因子的平方
        mvLevelSigma2[i]=mvScaleFactor[i]*mvScaleFactor[i];
    }

    //接下来的两个向量保存上面的参数的倒数
    mvInvScaleFactor.resize(nlevels);
    mvInvLevelSigma2.resize(nlevels);
    for(int i=0; i<nlevels; i++)
    {
        mvInvScaleFactor[i]=1.0f/mvScaleFactor[i];
        mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
    }

    //调整图像金字塔vector以使得其符合设定的图像层数
    mvImagePyramid.resize(nlevels);

    //每层需要提取出来的特征点个数,这个向量也要根据图像金字塔设定的层数进行调整
    mnFeaturesPerLevel.resize(nlevels);
    
    //图片降采样缩放系数的倒数
    float factor = 1.0f / scaleFactor;
    //第0层图像应该分配的特征点数量
    float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));

    //用于在特征点个数分配的,特征点的累计计数清空
    int sumFeatures = 0;
    //开始逐层计算要分配的特征点个数,顶层图像除外(看循环后面)
    for( int level = 0; level < nlevels-1; level++ )
    {
        //分配 cvRound : 返回个参数最接近的整数值
        mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
        //累计
        sumFeatures += mnFeaturesPerLevel[level];
        //乘系数
        nDesiredFeaturesPerScale *= factor;
    }
    //由于前面的特征点个数取整操作,可能会导致剩余一些特征点个数没有被分配,所以这里就将这个余出来的特征点分配到最高的图层中
    mnFeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);

    //成员变量pattern的长度,也就是点的个数,这里的512表示512个点(上面的数组中是存储的坐标所以是256*2*2)
    const int npoints = 512;
    //获取用于计算BRIEF描述子的随机采样点点集头指针
    //注意到pattern0数据类型为Points*,bit_pattern_31_是int[]型,所以这里需要进行强制类型转换
    const Point* pattern0 = (const Point*)bit_pattern_31_;	
    //使用std::back_inserter的目的是可以快覆盖掉这个容器pattern之前的数据
    //其实这里的操作就是,将在全局变量区域的、int格式的随机采样点以cv::point格式复制到当前类对象中的成员变量中
    std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));

    //This is for orientation
    //下面的内容是和特征点的旋转计算有关的
    // pre-compute the end of a row in a circular patch
    //预先计算圆形patch中行的结束位置
    //+1中的1表示那个圆的中间行
    umax.resize(HALF_PATCH_SIZE + 1);
    
    //cvFloor返回不大于参数的最大整数值,cvCeil返回不小于参数的最小整数值,cvRound则是四舍五入
    int v,		//循环辅助变量
        v0,		//辅助变量
        vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.f) / 2 + 1);	//计算圆的最大行号,+1应该是把中间行也给考虑进去了
                //NOTICE 注意这里的最大行号指的是计算的时候的最大行号,此行的和圆的角点在45°圆心角的一边上,之所以这样选择
                //是因为圆周上的对称特性
                
    //这里的二分之根2就是对应那个45°圆心角
    
    int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.f) / 2);
    //半径的平方
    const double hp2 = HALF_PATCH_SIZE*HALF_PATCH_SIZE;

    //利用圆的方程计算每行像素的u坐标边界(max)
    for (v = 0; v <= vmax; ++v)
        umax[v] = cvRound(sqrt(hp2 - v * v));		//结果都是大于0的结果,表示x坐标在这一行的边界

    // Make sure we are symmetric
    //这里其实是使用了对称的方式计算上四分之一的圆周上的umax,目的也是为了保持严格的对称(如果按照常规的想法做,由于cvRound就会很容易出现不对称的情况,
    //同时这些随机采样的特征点集也不能够满足旋转之后的采样不变性了)
    for (v = HALF_PATCH_SIZE, v0 = 0; v >= vmin; --v)
    {
        while (umax[v0] == umax[v0 + 1])
            ++v0;
        umax[v] = v0;
        DEBUG("%d=%d", v, v0);
        ++v0;
    }
}

 

四、结语

该章节主要讲解什么金字塔,以及特征点。并且提及到特征点包含了关键点以及描述子两个部分,但是没有做详细的介绍,再下一篇博客中会进行具体的讲解。最后我们还了解了ORBextractor 的构造函数,主要为接下来的内容做铺垫。
 
 
本文内容来自计算机视觉life ORB-SLAM2 课程课件

  • 5
    点赞
  • 9
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值