ORB-SLAM2 ---- ORBextractor::ComputeKeyPointsOctTree函数

目录

1.这个函数要做什么

2.代码解析1- 循环变量的定义及三层循环

2.1 代码

2.2 循环变量的含义

2.2.1 level循环的minBorderX、minBorderY、maxBorderX、maxBorderY

2.2.2 level循环的vToDistributeKeys、width 、height、nCols、nRows、wCell、hCell

2.2.3  第二层第三层遍历中的iniX、maxX、iniY、maxY

3.代码解析2- 三个循环做了什么 

3.代码解析2 - 平均分配关键点

4.代码解析3 -计算这些特征点的方向信息

5.调试运行


1.这个函数要做什么

        将每层图像金字塔图像分成一个个小块、并对对每一块用FAST算法提取特征点,由于提取的特征点数目肯定很多,我们需要按照ORBExtrator构造函数中要求的每层应该提取的特征点数目进行特征点筛选并分散特征点(离散化特征点并让特征点分布均匀),得到最终所有图像金字塔提取到的关键点,并且求出这些特征点的角度信息。

        我们定义了双层的vector容器存储所有的特征点,注意此处为二维的vector,第一维存储的是金字塔的层数,第二维存储的是那一层金字塔图像里提取的所有特征点。
    vector < vector<KeyPoint> > allKeypoints; 
    然后我们调用函数使用四叉树的方式计算每层图像的特征点并进行分配。回忆一下,我们是要将配置文件规定的特征点数目分配到各个金字塔层中,我们在上篇文章已经讲述了怎么把nFeatures个特征点分配到nLevels中,然而只是规定了数目,具体怎么分布没定,再通俗易懂的说,上一步(下面链接)我们只是创建了金字塔规定了每层金字塔分配多少,但它还是个空金字塔,这个函数我们将此空金字塔填满!

ORB-SLAM2 ---- ORBextractor::ComputePyramid函数_Courage2022的博客-CSDN博客

# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1000

# ORB Extractor: Scale factor between levels in the scale pyramid 	
ORBextractor.scaleFactor: 1.2

# ORB Extractor: Number of levels in the scale pyramid	
ORBextractor.nLevels: 8

2.代码解析1- 循环变量的定义及三层循环

2.1 代码

//计算四叉树的特征点,函数名字后面的OctTree只是说明了在过滤和分配特征点时所使用的方式
void ORBextractor::ComputeKeyPointsOctTree(
	vector<vector<KeyPoint> >& allKeypoints)	//所有的特征点,这里第一层vector存储的是某图层里面的所有特征点,
												//第二层存储的是整个图像金字塔中的所有图层里面的所有特征点
{
	//allKeypoints是存放不同层数的所有特征点,有nlevel层,初始化一下
    allKeypoints.resize(nlevels);
	//图像cell的尺寸,是个正方形,可以理解为边长in像素坐标
    const float W = 30;

    // 对每一层图像做处理
    for (int level = 0; level < nlevels; ++level)
    {
		//计算这层图像的坐标边界,算上扩充的3
        const int minBorderX = EDGE_THRESHOLD-3;			
        const int minBorderY = minBorderX;					
        const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
        const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;

		//存储需要进行平均分配的特征点
        vector<cv::KeyPoint> vToDistributeKeys;

		//一般地都是过量采集,所以这里预分配的空间大小是nfeatures*10
        vToDistributeKeys.reserve(nfeatures*10);

		//计算进行特征点提取的图像区域尺寸
        const float width = (maxBorderX-minBorderX);
        const float height = (maxBorderY-minBorderY);

		//计算网格在当前层的图像有的行数和列数
        const int nCols = width/W;
        const int nRows = height/W;

		//计算每个图像网格所占的像素
        const int wCell = ceil(width/nCols);         
        const int hCell = ceil(height/nRows);

		//开始遍历图像网格,还是以行开始遍历的
        for(int i=0; i<nRows; i++)
        {
			//计算当前网格初始行坐标
            const float iniY =minBorderY+i*hCell;
            float maxY = iniY+hCell+6;

			//如果初始的行坐标就已经超过了有效的图像边界了,下一行
            if(iniY>=maxBorderY-3)
                continue;
			//如果图像的大小导致不能够正好划分出来整齐的图像网格,那么就把提取特征点的区域缩小一些
            if(maxY>maxBorderY)
                maxY = maxBorderY;

			//开始列的遍历
            for(int j=0; j<nCols; j++)
            {
                const float iniX =minBorderX+j*wCell;
                float maxX = iniX+wCell+6;				
                if(iniX>=maxBorderX-3)
                    continue;
                if(maxX>maxBorderX)
                    maxX = maxBorderX;
				//这个容器存储提取到的特征点
                vector<cv::KeyPoint> vKeysCell;
				//FAST提取特征点,调用opencv的库函数来检测FAST角点
                FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),	//待检测的图像,这里就是当前遍历到的图像块
                     vKeysCell,			//存储角点位置的容器
					 iniThFAST,			//检测阈值
					 true);				//使能非极大值抑制

				//如果这个图像块中使用默认的FAST检测阈值没有能够检测到角点
                if(vKeysCell.empty())
                {
					//那么就使用更低的阈值来进行重新检测
                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),	//待检测的图像
                         vKeysCell,		//存储角点位置的容器
						 minThFAST,		//更低的检测阈值
						 true);			//使能非极大值抑制
                }

                //当图像cell中检测到FAST角点的时候执行下面的语句
                if(!vKeysCell.empty())
                {
					//遍历其中的所有FAST角点
                    for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
                    {
						//NOTICE 到目前为止,这些角点的坐标都是基于图像cell的,现在我们要先将其恢复到当前的【坐标边界】下的坐标
						//这样做是因为在下面使用八叉树法整理特征点的时候将会使用得到这个坐标
						//在后面将会被继续转换成为在当前图层的扩充图像坐标系下的坐标
                        (*vit).pt.x+=j*wCell;
                        (*vit).pt.y+=i*hCell;
						//然后将其加入到”等待被分配“的特征点容器中
                        vToDistributeKeys.push_back(*vit);
                    }//遍历图像cell中的所有的提取出来的FAST角点,并且恢复其在整个金字塔当前层图像下的坐标
                }//当图像cell中检测到FAST角点的时候执行下面的语句
            }//开始遍历图像cell的列
        }//开始遍历图像cell的行

        //声明一个对当前图层的特征点的容器的引用
        vector<KeyPoint> & keypoints = allKeypoints[level];
		//并且调整其大小为欲提取出来的特征点个数(当然这里也是扩大了的,因为不可能所有的特征点都是在这一个图层中提取出来的)
        keypoints.reserve(nfeatures);

        // 根据mnFeatuvector<KeyPoint> & keypoints = allKeypoints[level];resPerLevel,即该层的兴趣点数,对特征点进行剔除
		//返回值是一个保存有特征点的vector容器,含有剔除后的保留下来的特征点
        //得到的特征点的坐标,依旧是在当前图层下来讲的
        keypoints = DistributeOctTree(vToDistributeKeys, 			//当前图层提取出来的特征点,也即是等待剔除的特征点
																	//NOTICE 注意此时特征点所使用的坐标都是在“半径扩充图像”下的
									  minBorderX, maxBorderX,		//当前图层图像的边界,而这里的坐标却都是在“边缘扩充图像”下的
                                      minBorderY, maxBorderY,
									  mnFeaturesPerLevel[level], 	//希望保留下来的当前层图像的特征点个数
									  level);						//当前层图像所在的图层

		//PATCH_SIZE是对于底层的初始图像来说的,现在要根据当前图层的尺度缩放倍数进行缩放得到缩放后的PATCH大小 和特征点的方向计算有关
        const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];

        // Add border to coordinates and scale information
		//获取剔除过程后保留下来的特征点数目
        const int nkps = keypoints.size();
		//然后开始遍历这些特征点,恢复其在当前图层图像坐标系下的坐标
        for(int i=0; i<nkps ; i++)
        {
			//对每一个保留下来的特征点,恢复到相对于当前图层“边缘扩充图像下”的坐标系的坐标
            keypoints[i].pt.x+=minBorderX;
            keypoints[i].pt.y+=minBorderY;
			//记录特征点来源的图像金字塔图层
            keypoints[i].octave=level;
			//记录计算方向的patch,缩放后对应的大小, 又被称作为特征点半径
            keypoints[i].size = scaledPatchSize;
        }
    }

    // compute orientations
    //然后计算这些特征点的方向信息,注意这里还是分层计算的
    for (int level = 0; level < nlevels; ++level)
        computeOrientation(mvImagePyramid[level],	//对应的图层的图像
						   allKeypoints[level], 	//这个图层中提取并保留下来的特征点容器
						   umax);					//以及PATCH的横坐标边界
}

2.2 循环变量的含义

2.2.1 level循环的minBorderX、minBorderY、maxBorderX、maxBorderY

        我们定义了第一层(对图像金字塔的每一个level )循环变量minBorderX、minBorderY、maxBorderX、maxBorderY,如下图所示:

        因此图像的坐标边界就是原图像扩充了3个像素值,为什么扩充像素值上篇文章我已经说过,不再赘述! 

2.2.2 level循环的vToDistributeKeys、width 、height、nCols、nRows、wCell、hCell

        在代码中我们调试一下:

         在图像金字塔的第0层,参数如上。

2.2.3  第二层第三层遍历中的iniX、maxX、iniY、maxY

        假设我们第一次循环,各变量如下图所示:

        那为什么要加6呢?还是因为边缘匹配特征点的缘故,我们在图像外面加个3像素的壳子、确保边缘的部分可以提取出特征点! 

3.代码解析2- 三个循环做了什么 

        第一层for循环:算出每一层的循环遍变量、供下面两层使用

        第二层for循环:对每一行进行遍历,算出初始与最大行坐标,上一层的maxY和下一层的iniY如图所示,这样是因为有6的缘故。

         此外,如果初始化的iniY大于边界-3,说明已经超过图像边界了,为什么是-3呢,因为我们用FAST提取关键点时为了避免边界无法提取的情况,要在外面加上个半径为3的外壳,这也是为什么加6的原因。如果iniY大于边界-3的话,那就说明壳子到边界了。

        此外,如果该网格的最大Y坐标超越了边界坐标,就让最大的Y坐标变成边界坐标。

        列的遍历也是如此。

        在最内层循环中,我们用一个容器vector<cv::KeyPoint> vKeysCell存储当前网格提取出的特征点。调用opencv的内置函数提取特征点。

FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),	//待检测的图像,这里就是当前遍历到的图像块
                     vKeysCell,			//存储角点位置的容器
					 iniThFAST,			//检测阈值
					 true);				//使能非极大值抑制

				//如果这个图像块中使用默认的FAST检测阈值没有能够检测到角点
                if(vKeysCell.empty())
                {
					//那么就使用更低的阈值来进行重新检测
                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),	//待检测的图像
                         vKeysCell,		//存储角点位置的容器
						 minThFAST,		//更低的检测阈值
						 true);			//使能非极大值抑制
                }

        这里我们先用了高标准的阈值提取特征点...如果提取不出来(可能是边缘的图像或者灰度变化不大的图像)我们再用低标准的阈值提取特征点,存放在vKeysCell容器中。

        

 //当图像cell中检测到FAST角点的时候执行下面的语句
                if(!vKeysCell.empty())
                {
					//遍历其中的所有FAST角点
                    for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
                    {
						//NOTICE 到目前为止,这些角点的坐标都是基于图像cell的,现在我们要先将其恢复到当前的【坐标边界】下的坐标
						//这样做是因为在下面使用八叉树法整理特征点的时候将会使用得到这个坐标
						//在后面将会被继续转换成为在当前图层的扩充图像坐标系下的坐标
                        (*vit).pt.x+=j*wCell;
                        (*vit).pt.y+=i*hCell;
						//然后将其加入到”等待被分配“的特征点容器中
                        vToDistributeKeys.push_back(*vit);
                    }//遍历图像cell中的所有的提取出来的FAST角点,并且恢复其在整个金字塔当前层图像下的坐标
                }//当图像cell中检测到FAST角点的时候执行下面的语句

        在第三层循环的最后,我们要恢复从opencv提取特征点的坐标到我们的金字塔图像中,并将提取到的特征点放入vToDistributeKeys容器中。

3.代码解析2 - 平均分配关键点

        由于我们在上步中对每一个小方格的进行特征点提取、会出现小方格特征点分布不均匀,比如某一个小方格特征点及其不均匀有很多...。另外,我们在ORBExtrator构造函数中定义了每层应该提取出的特征点数目。因此我们要做的是离散化特征点并让特征点分布均匀。

        //声明一个对当前图层的特征点的容器的引用
        vector<KeyPoint> & keypoints = allKeypoints[level];
		//并且调整其大小为欲提取出来的特征点个数(当然这里也是扩大了的,因为不可能所有的特征点都是在这一个图层中提取出来的)
        keypoints.reserve(nfeatures);

        // 根据mnFeatuvector<KeyPoint> & keypoints = allKeypoints[level];resPerLevel,即该层的兴趣点数,对特征点进行剔除
		//返回值是一个保存有特征点的vector容器,含有剔除后的保留下来的特征点
        //得到的特征点的坐标,依旧是在当前图层下来讲的
        keypoints = DistributeOctTree(vToDistributeKeys, 			//当前图层提取出来的特征点,也即是等待剔除的特征点
																	//NOTICE 注意此时特征点所使用的坐标都是在“半径扩充图像”下的
									  minBorderX, maxBorderX,		//当前图层图像的边界,而这里的坐标却都是在“边缘扩充图像”下的
                                      minBorderY, maxBorderY,
									  mnFeaturesPerLevel[level], 	//希望保留下来的当前层图像的特征点个数
									  level);						//当前层图像所在的图层

		//PATCH_SIZE是对于底层的初始图像来说的,现在要根据当前图层的尺度缩放倍数进行缩放得到缩放后的PATCH大小 和特征点的方向计算有关
        const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];

        // Add border to coordinates and scale information
		//获取剔除过程后保留下来的特征点数目
        const int nkps = keypoints.size();
		//然后开始遍历这些特征点,恢复其在当前图层图像坐标系下的坐标
        for(int i=0; i<nkps ; i++)
        {
			//对每一个保留下来的特征点,恢复到相对于当前图层“边缘扩充图像下”的坐标系的坐标
            keypoints[i].pt.x+=minBorderX;
            keypoints[i].pt.y+=minBorderY;
			//记录特征点来源的图像金字塔图层
            keypoints[i].octave=level;
			//记录计算方向的patch,缩放后对应的大小, 又被称作为特征点半径
            keypoints[i].size = scaledPatchSize;
        }
    }

        allkeyPoints容器存储了最终提取的特征点结果,我们声明了临时变量keypoints声明一个对当前图层的特征点的容器的引用,将其重调整其大小为欲提取出来的特征点个数,然后利用DistributeOctTree算法将特征点分布平均化并剔除,恢复特征点在原来坐标系下的坐标。

DistributeOctTree函数解析:

ORB-SLAM2 ---- ORBextractor::DistributeOctTree函数_Courage2022的博客-CSDN博客

4.代码解析3 -计算这些特征点的方向信息

    // compute orientations
    //然后计算这些特征点的方向信息,注意这里还是分层计算的
    for (int level = 0; level < nlevels; ++level)
        computeOrientation(mvImagePyramid[level],	//对应的图层的图像
						   allKeypoints[level], 	//这个图层中提取并保留下来的特征点容器
						   umax);		

(1条消息) ORB-SLAM2 ---- IC_Angle函数_Courage2022的博客-CSDN博客

5.调试运行

        如果你对上述不太清晰的话,我们到Clion中调试一下:

        我们拿图像金字塔的第0层为例:

        从调试信息可以看出,第一层的图像是480\times572的,我们再看看行列的调试信息:

         我们画出示意图:

        这里我们把图像分成了24*14份,对每一份进行特征点的提取。

        为保证普适性,我们拿i=2,j=3时举例子:

        对图示区域进行FAST特征点提取:

        我们看一下特征点的调试信息,特征点有x,y信息,但是其都是针对坐标(0,0)的,我们要将其恢复到网格中。装入变量vToDistributeKeys中。

        因为我们计算的尺度一直是如图红色区域:

        最终要恢复在(0,0)下,因此我们需要对每个特征点执行如下操作恢复在大图下的坐标并记录一下信息:

        for(int i=0; i<nkps ; i++)
        {
			//对每一个保留下来的特征点,恢复到相对于当前图层“边缘扩充图像下”的坐标系的坐标
            keypoints[i].pt.x+=minBorderX;
            keypoints[i].pt.y+=minBorderY;
			//记录特征点来源的图像金字塔图层
            keypoints[i].octave=level;
			//记录计算方向的patch,缩放后对应的大小, 又被称作为特征点半径
            keypoints[i].size = scaledPatchSize;
        }
  • 4
    点赞
  • 14
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 1
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

打赏作者

APS2023

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

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

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

打赏作者

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

抵扣说明:

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

余额充值