ORB-SLAM2 代码(+理论)解析(四): Tracking 线程 —— ORB特征点提取

ORB特征提取是 Tracking线程 中首先要做的事情,只有从图像中提取了特征,才能对camera中传入的一帧一帧的图像按照特征值来进行跟踪,进而来估计相机的位姿。

上一节博客中: https://blog.csdn.net/hltt3838/article/details/115096997, 最后我们介绍了  2.2.1 中Frame.cc 程序,里面包含特征点提取函数: ExtractORB(0,imGray)

 

一、ExtractORB(int flag, const cv::Mat &im)

/*
提取图像的ORB特征点,提取的 关键点存放在mvKeys,描述子存放在mDescriptors
flag :         标记是左图还是右图。0:左图  1:右图
im   :         等待提取特征点的图像
*/
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);
}

注意:ExtractORB函数中调用了重载的()操作符函数 ORBextractor::operator(),该函数代码如下:

 

二、ORBextractor::operator()

具体流程:

1.对于输入的图片,计算其图像金字塔;

2.提取图像金字塔中各层图像的关键点;

3.计算提取出的关键点对应的描述子;

符号含义:

 用仿函数(重载括号运算符)              方法来计算图像特征点
param[in] _image                                    输入原始图的图像
param[in] _mask                                     掩膜mask
param[in & out] _keypoints                存储特征点关键点的向量
param[in & out] _descriptors             存储特征点描述子的矩阵

void ORBextractor::operator()( InputArray _image, InputArray _mask, vector<KeyPoint>& _keypoints,
                      OutputArray _descriptors)
{ 
    // Step 1 检查图像有效性。如果图像为空,那么就直接返回
    if(_image.empty())
        return;

    //获取图像的大小
    Mat image = _image.getMat();

    //判断图像的格式是否正确,要求是单通道灰度值
    assert(image.type() == CV_8UC1 );

    // Pre-compute the scale pyramid
    // Step 2 构建图像金字塔
    ComputePyramid(image);

    // Step 3 计算图像的特征点,并且将特征点进行均匀化。均匀的特征点可以提高位姿计算精度
    // 存储所有的特征点,注意此处为二维的vector,第一维存储的是金字塔的层数,第二维存储的是那一层金字塔图像里提取的所有特征点
    vector < vector<KeyPoint> > allKeypoints; 

    //使用四叉树的方式计算每层图像的特征点并进行分配
    ComputeKeyPointsOctTree(allKeypoints);

    //使用传统的方法提取并平均分配图像的特征点,作者并未使用
    //ComputeKeyPointsOld(allKeypoints);

	
    // Step 4 拷贝图像描述子到新的矩阵descriptors
    Mat descriptors;

    //统计整个图像金字塔中的特征点
    int nkeypoints = 0;

    //开始遍历每层图像金字塔,并且累加每层的特征点个数
    for (int level = 0; level < nlevels; ++level)
        nkeypoints += (int)allKeypoints[level].size();
	
    //如果本图像金字塔中没有任何的特征点
    if( nkeypoints == 0 )
    //通过调用cv::mat类的.realse方法,强制清空矩阵的引用计数,这样就可以强制释放矩阵的数据了
    //参考[https://blog.csdn.net/giantchen547792075/article/details/9107877]
        _descriptors.release();
    else
    {
   //如果图像金字塔中有特征点,那么就创建这个存储描述子的矩阵,注意这个矩阵是存储整个图像金字塔中特征点的描述子的
        _descriptors.create(nkeypoints,		//矩阵的行数,对应为特征点的总个数
				32, 		//矩阵的列数,对应为使用32*8=256位描述子
				CV_8U);	        //矩阵元素的格式
		//获取这个描述子的矩阵信息
		// ?为什么不是直接在参数_descriptors上对矩阵内容进行修改,而是重新新建了一个变量,复制矩阵后,在这个新建变量的基础上进行修改?
        descriptors = _descriptors.getMat();
     }

    //清空用作返回特征点提取结果的vector容器
    _keypoints.clear();
    //并预分配正确大小的空间
    _keypoints.reserve(nkeypoints);

    //因为遍历是一层一层进行的,但是描述子那个矩阵是存储整个图像金字塔中特征点的描述子,所以在这里设置了Offset变量来保存“寻址”时的偏移量,
    //辅助进行在总描述子mat中的定位
    int offset = 0;

    //开始遍历每一层图像
    for (int level = 0; level < nlevels; ++level)
    {
	//获取在allKeypoints中当前层特征点容器的句柄
        vector<KeyPoint>& keypoints = allKeypoints[level];

	//本层的特征点数
        int nkeypointsLevel = (int)keypoints.size();

	//如果特征点数目为0,跳出本次循环,继续下一层金字塔
        if(nkeypointsLevel==0)
            continue;

        // preprocess the resized image 
        //  Step 5 对图像进行高斯模糊
	// 深拷贝当前金字塔所在层级的图像
        Mat workingMat = mvImagePyramid[level].clone();

	// 注意:提取特征点的时候,使用的是清晰的原图像;这里计算描述子的时候,为了避免图像噪声的影响,使用了高斯模糊
        GaussianBlur(workingMat, 		//源图像
		     workingMat, 		//输出图像
		    Size(7, 7), 		//高斯滤波器kernel大小,必须为正的奇数
			2, 		        //高斯滤波在x方向的标准差
			2, 			//高斯滤波在y方向的标准差
			 BORDER_REFLECT_101);   //边缘拓展点插值类型

        // Compute the descriptors 计算描述子
	// desc存储当前图层的描述子
        Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);

	// Step 6 计算高斯模糊后图像的描述子
        computeDescriptors(workingMat, 	//高斯模糊之后的图层图像
			keypoints, 	//当前图层中的特征点集合
			desc, 		//存储计算之后的描述子
			pattern);	//随机采样点集

	// 更新偏移量的值 
        offset += nkeypointsLevel;

        // Scale keypoint coordinates
	// Step 6 对非第0层图像中的特征点的坐标恢复到第0层图像(原图像)的坐标系下
        // ? 得到所有层特征点在第0层里的坐标放到_keypoints里面
	// 对于第0层的图像特征点,他们的坐标就不需要再进行恢复了
        if (level != 0)
        {
	    // 获取当前图层上的缩放系数
            float scale = mvScaleFactor[level];
            // 遍历本层所有的特征点
            for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
                 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)

		// 特征点本身直接乘缩放倍数就可以了
                keypoint->pt *= scale;
        }
        
        // And add the keypoints to the output
        // 将keypoints中内容插入到_keypoints 的末尾
        // keypoint其实是对allkeypoints中每层图像中特征点的引用,这样allkeypoints中的所有特征点在这里被转存到输出的_keypoints
        _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
    }
}

 

2.1 ORBextractor::ComputePyramid(cv::Mat image)

功能:构建图像金字塔,将原始图像 按照比例 缩小并依次存在 mvImagePyramid全局变量) 里

程序

void ORBextractor::ComputePyramid(cv::Mat image)
{
    //开始遍历所有的图层
    for (int level = 0; level < nlevels; ++level)
    {
	//获取本层图像的缩放系数
        float scale = mvInvScaleFactor[level];

	//计算本层图像的像素尺寸大小
        Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
	//全尺寸图像。包括无效图像区域的大小。将图像进行“补边”,EDGE_THRESHOLD区域外的图像不进行FAST角点检测
        Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);

	// 定义了两个变量:temp是扩展了边界的图像,masktemp并未使用
        Mat temp(wholeSize, image.type()), masktemp;

        // mvImagePyramid 刚开始时是个空的vector<Mat>
	// 把图像金字塔该图层的图像指针mvImagePyramid指向temp的中间部分(这里为浅拷贝,内存相同)
        mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));

        // Compute the resized image
	//计算第0层以上resize后的图像
        if( level != 0 )
        {
	    //将上一层金字塔图像根据设定sz缩放到当前层级
            // resize(mvImagePyramid[level-1],	//输入图像
			//    mvImagePyramid[level], //输出图像
			//   sz, 			//输出图像的尺寸
			//   0, 			//水平方向上的缩放系数,留0表示自动计算
			//   0,  			//垂直方向上的缩放系数,留0表示自动计算
			//   cv::INTER_LINEAR);	//图像缩放的差值算法类型,这里的是线性插值算法

            //!  原代码mvImagePyramid 并未扩充,上面resize应该改为如下

            resize(image,	   //输入图像
		  mvImagePyramid[level], 	//输出图像
		  sz, 			//输出图像的尺寸
		  0, 			//水平方向上的缩放系数,留0表示自动计算
		  0,  			//垂直方向上的缩放系数,留0表示自动计算
		  cv::INTER_LINEAR);	//图像缩放的差值算法类型,这里的是线性插值算法

	//把源图像拷贝到目的图像的中央,四面填充指定的像素。图片如果已经拷贝到中间,只填充边界
	//这样做是为了能够正确提取边界的FAST角点

	//EDGE_THRESHOLD指的这个边界的宽度,由于这个边界之外的像素不是原图像素而是算法生成出来的,所以不能够在EDGE_THRESHOLD之外提取特征点	
		
            copyMakeBorder(mvImagePyramid[level],   //源图像
			temp, 			     //目标图像(此时其实就已经有大了一圈的尺寸了)
		 EDGE_THRESHOLD, EDGE_THRESHOLD,     //top & bottom 需要扩展的border大小
		EDGE_THRESHOLD, EDGE_THRESHOLD,	         //left & right 需要扩展的border大小
                 BORDER_REFLECT_101+BORDER_ISOLATED);     //扩充方式,opencv给出的解释:
			
			/*Various border types, image boundaries are denoted with '|'
			* BORDER_REPLICATE:     aaaaaa|abcdefgh|hhhhhhh
			* BORDER_REFLECT:       fedcba|abcdefgh|hgfedcb
			* BORDER_REFLECT_101:   gfedcb|abcdefgh|gfedcba
			* BORDER_WRAP:          cdefgh|abcdefgh|abcdefg
			* BORDER_CONSTANT:      iiiiii|abcdefgh|iiiiiii  with some specified 'i'
			*/
			
	    //BORDER_ISOLATED	表示对整个图像进行操作
 // https://docs.opencv.org/3.4.4/d2/de8/group__core__array.html#ga2ac1049c2c3dd25c2b41bffe17658a36

        }
        else
        {
	   //对于第0层未缩放图像,直接将图像深拷贝到temp的中间,
            //并且对其周围进行边界扩展。此时temp就是对原图扩展后的图像
            copyMakeBorder(image,	//这里是原图像
			   temp, EDGE_THRESHOLD, EDGE_THRESHOLD, 
                           EDGE_THRESHOLD, EDGE_THRESHOLD,
                           BORDER_REFLECT_101);            
        }
        //! 原代码mvImagePyramid 并未扩充,应该添加下面一行代码
        mvImagePyramid[level] = temp;
    }

}

} //namespace ORB_SLAM

理论:

这个函数主要是生成了nlevels 张不同缩放尺度的图片放入mvImagePyramid中;当 nlevels=8 时,其生成的图片为:

其中 image 为原始图片,image0~7对应为 mvImagePyramid 中图片。

生成 mvImagePyramid[i] 的图片的方法是:

  1.     先用 resize() 将图片缩放至sz大小,放入 mvImagePyramid[i]
  2.     接着用 copyMakeBorder() 扩展边界至 wholeSize 大小放入temp;
  3.     注意 temp 和mvImagePyramid[i] 公用相同数据区,改变temp会改变mvImagePyramid[i]。

 

图像填充

 

参考
resize()用法
OpenCV(3)-图像resize
copyMakeBorder()用法
OpenCV图像剪切的扩展和高级用法:任意裁剪,边界扩充

 

 

2.2 ORBextractor::ComputeKeyPointsOctTree()

 功能:提取图像金字塔中各层图像的关键点并储存在 allKeypoints里,函数名字后面的OctTree只是说明了在过滤和分配特征点时所使用的方式
 算法具体步骤描述:
 1.先是计算提取关键点的边界,太边缘的地方放弃提取关键点;
 2.将图像分割为W*W的小图片,遍历这些分割出来的小图片并提取其关键点;
 3.将提取的关键点交给 DistributeOctTree() 利用四叉树以及非极大值抑制算法进行筛选;
 4.计算关键点的相关信息:像素位置,patch尺度,方向,所在高斯金字塔层数;
 注意:在分割图片的时候,小窗之间是有重叠的
 

程序

//利用四叉树提取高斯金字塔中每层图像的orb关键点
void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint> >& allKeypoints)
{
	
//所有的特征点,这里第一层vector存储的是某图层里面的所有特征点,
//第二层存储的是整个图像金字塔中的所有图层里面的所有特征点

    allKeypoints.resize(nlevels);
	
   //图像cell的尺寸,是个正方形,可以理解为边长in像素坐标
    const float W = 30;
	
   // 对每一层图像做处理 ,遍历所有图像
   //对高斯金字塔mvImagePyramid中每层图像提取orb特征点
    for (int level = 0; level < nlevels; ++level)
    {
       //计算这层图像的坐标边界,在这个边界内计算FAST关键点; NOTICE 注意这里是坐标边界,EDGE_THRESHOLD指的应该是可以提取特征点的有效图像边界,后面会一直使用“有效图像边界“这个自创名词

      //这里的3是因为在计算FAST特征点的时候,需要建立一个半径为3的圆
        const int minBorderX = EDGE_THRESHOLD-3;
        const int minBorderY = minBorderX; //minY的计算就可以直接拷贝上面的计算结果了
        const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
        const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
		
	//用这个存储待筛选的orb
        vector<cv::KeyPoint> vToDistributeKeys;
        vToDistributeKeys.reserve(nfeatures*10);
		
	//计算边界宽度和高度
        const float width = (maxBorderX-minBorderX);
        const float height = (maxBorderY-minBorderY);
		
	//将原始图片分割的行数和列数; 每一个网格是w*w,有很多这样的网格
        const int nCols = width/W;
        const int nRows = height/W;

        //实际分割窗口的大小
        const int wCell = ceil(width/nCols);
        const int hCell = ceil(height/nRows);
		
	//使用两个for循环遍历每个窗口,首先先计算窗口的四个坐标
	//遍历每行
        for(int i=0; i<nRows; i++)
        {	
        //iniY,maxY为窗口的行上坐标和下坐标
        //计算(iniY,maxY)坐标

          const float iniY =minBorderY+i*hCell;
          //这里注意窗口之间有6行的重叠
            float maxY = iniY+hCell+6;
			
	  //窗口的行上坐标超出边界,则放弃此行
            if(iniY>=maxBorderY-3)
                continue;

            //窗口的行下坐标超出边界,则将窗口的行下坐标设置为边界
            if(maxY>maxBorderY)
                maxY = maxBorderY;
                
	    //遍历每列
            for(int j=0; j<nCols; j++)
            {
            	//iniX,maxX为窗口的列左坐标和右坐标
            	//计算(iniX,maxX)坐标
                const float iniX =minBorderX+j*wCell;
                //这里注意窗口之间有6列的重叠
                float maxX = iniX+wCell+6;

		//窗口的列左坐标超出边界,则放弃此列
               	//判断坐标是否在图像中
		//TODO 不太能够明白为什么要-6,前面不都是-3吗
		//!BUG  正确应该是maxBorderX-3
                if(iniX>=maxBorderX-6)
                    continue;

                //窗口的列右坐标超出边界,则将窗口的列右坐标设置为边界
                if(maxX>maxBorderX)
                    maxX = maxBorderX;
				
		//每个小窗里的关键点KeyPoint将存在这里
                vector<cv::KeyPoint> vKeysCell;
                
                //提取FAST角点
                //输入参数
                //mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX) level层的图片中行
                //范围(iniY,maxY),列范围(iniX,maxX)的截图
                //
                //vKeysCell,储存提取的fast关键点
                //iniThFAST提取角点的阈值
                //true 是否开启非极大值抑制算法
                FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                     vKeysCell,iniThFAST,true);
				
		// 如果没有找到FAST关键点,就降低阈值重新计算FAST
                if(vKeysCell.empty())
                {
                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                         vKeysCell,minThFAST,true);
                }
				
		//如果找到的点不为空,就加入到vToDistributeKeys
                if(!vKeysCell.empty())
                {
                    for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
                    {
            //根据前面的行列计算实际的位置
            //这些角点的坐标都是基于图像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);
		
	//筛选vToDistributeKeys中的关键点
        keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
                                      minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);
		
	//计算在本层提取出的关键点对应的Patch大小,称为scaledPatchSize
	//你想想,本层的图像是缩小的,而你在本层提取的orb特征点,计算orb的方向,描述子的时候根据
	//的PATCH大小依旧是PATCH_SIZE。
	//而你在本层提取的orb是要恢复到原始图像上去的,所以其特征点的size(代表特征点的尺度信息)需要放大。
        const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];

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

理论

边界计算

2.2.1 类方法ORBextractor::DistributeOctTree()

 

使用四叉树对金字塔每一图层中的特征点进行平均和分发,使得筛选后的特征点数量在预计的范围,并且分布均匀;
1、如果图片的宽度比较宽,就先把分成左右 w/h 份;一般的 640×480 的图像开始的时候只有一个 node。
2、如果 node 里面的点数 >1 ,把每个 node 分成四个 node ,如果 node 里面的特征点为空,就不要了, 删掉。
3、新分的 node 的点数 >1 ,就再分裂成 4 个 node 。如此,一直分裂。
4、终止条件为: node 的总数量 > [ 公式 ] ,或者无法再进行分裂。
5、然后从每个 node 里面选择一个质量最好的 FAST 点。

程序部分:

vector<cv::KeyPoint> ORBextractor::DistributeOctTree(const vector<cv::KeyPoint>& vToDistributeKeys, const int &minX, const int &maxX, const int &minY, const int &maxY, const int &N, const int &level)
{
    // Compute how many initial nodes
    // Step 1 根据宽高比确定初始节点数目
    //计算应该生成的初始节点个数,根节点的数量nIni是根据边界的宽高比值确定的,一般是1或者2
    // ! bug: 如果宽高比小于0.5,nIni=0, 后面hx会报错
    const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));

        //一个初始的节点的x方向有多少个像素
    const float hX = static_cast<float>(maxX-minX)/nIni;

	//存储有提取器节点的列表
    list<ExtractorNode> lNodes;

	//存储初始提取器节点指针的vector
    vector<ExtractorNode*> vpIniNodes;

	//然后重新设置其大小
    vpIniNodes.resize(nIni);

	// Step 2 生成初始提取器节点
    for(int i=0; i<nIni; i++)
    {      
		//生成一个提取器节点
        ExtractorNode ni;

		//设置提取器节点的图像边界
		//注意这里和提取FAST角点区域相同,都是“半径扩充图像”,特征点坐标从0 开始 
        ni.UL = cv::Point2i(hX*static_cast<float>(i),0);    //UpLeft
        ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);  //UpRight
		ni.BL = cv::Point2i(ni.UL.x,maxY-minY);     //BottomLeft
        ni.BR = cv::Point2i(ni.UR.x,maxY-minY);             //BottomRight

		//重设vkeys大小
        ni.vKeys.reserve(vToDistributeKeys.size());

	//将刚才生成的提取节点添加到列表中
	//虽然这里的ni是局部变量,但是由于这里的push_back()是拷贝参数的内容到一个新的对象中然后再添加到列表中
	//所以当本函数退出之后这里的内存不会成为“野指针”
        lNodes.push_back(ni);
	//存储这个初始的提取器节点句柄
        vpIniNodes[i] = &lNodes.back();
    }

    //Associate points to childs
    // Step 3 将特征点分配到子提取器节点中
    for(size_t i=0;i<vToDistributeKeys.size();i++)
    {
	//获取这个特征点对象
        const cv::KeyPoint &kp = vToDistributeKeys[i];
	//按特征点的横轴位置,分配给属于那个图像区域的提取器节点(最初的提取器节点)
        vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
    }
    
    // Step 4 遍历此提取器节点列表,标记那些不可再分裂的节点,删除那些没有分配到特征点的节点
    // ? 这个步骤是必要的吗?感觉可以省略,通过判断nIni个数和vKeys.size() 就可以吧
    list<ExtractorNode>::iterator lit = lNodes.begin();
    while(lit!=lNodes.end())
    {
	//如果初始的提取器节点所分配到的特征点个数为1
        if(lit->vKeys.size()==1)
        {
	        //那么就标志位置位,表示此节点不可再分
            lit->bNoMore=true;
		//更新迭代器
            lit++;
        }
               //如果一个提取器节点没有被分配到特征点,那么就从列表中直接删除它
        else if(lit->vKeys.empty())
             //注意,由于是直接删除了它,所以这里的迭代器没有必要更新;否则反而会造成跳过元素的情况
            lit = lNodes.erase(lit);			
        else
	      //如果上面的这些情况和当前的特征点提取器节点无关,那么就只是更新迭代器 
            lit++;
    }

    //结束标志位清空
    bool bFinish = false;

    //记录迭代次数,只是记录,并未起到作用
    int iteration = 0;

	//声明一个vector用于存储节点的vSize和句柄对
	//这个变量记录了在一次分裂循环中,那些可以再继续进行分裂的节点中包含的特征点数目和其句柄
    vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;

	//调整大小,这里的意思是一个初始化节点将“分裂”成为四个,当然实际上不会有那么多,这里多分配了一些只是预防万一
    vSizeAndPointerToNode.reserve(lNodes.size()*4);

    // Step 5 根据兴趣点分布,利用4叉树方法对图像进行划分区域
    while(!bFinish)
    {
	//更新迭代次数计数器,只是记录,并未起到作用
        iteration++;

	//保存当前节点个数,prev在这里理解为“保留”比较好
        int prevSize = lNodes.size();

	//重新定位迭代器指向列表头部
        lit = lNodes.begin();

	//需要展开的节点计数,这个一直保持累计,不清零
        int nToExpand = 0;

	//因为是在循环中,前面的循环体中可能污染了这个变量,so清空这个vector
	//这个变量也只是统计了某一个循环中的点
	//这个变量记录了在一次分裂循环中,那些可以再继续进行分裂的节点中包含的特征点数目和其句柄
        vSizeAndPointerToNode.clear();

        // 将目前的子区域进行划分
	//开始遍历列表中所有的提取器节点,并进行分解或者保留
        while(lit!=lNodes.end())
        {
		//如果提取器节点只有一个特征点,
            if(lit->bNoMore)
            {
		//那么就没有必要再进行细分了
                lit++;

		//跳过当前节点,继续下一个
                continue;
            }
            else
            {
                // If more than one point, subdivide
		//如果当前的提取器节点具有超过一个的特征点,那么就要进行继续细分
                ExtractorNode n1,n2,n3,n4;

		//再细分成四个子区域
                lit->DivideNode(n1,n2,n3,n4); 

                // Add childs if they contain points
	//如果这里分出来的子区域中有特征点,那么就将这个子区域的节点添加到提取器节点的列表中
		//注意这里的条件是,有特征点即可
                if(n1.vKeys.size()>0)
                {
		//注意这里也是添加到列表前面的
                    lNodes.push_front(n1);   

		//再判断其中子提取器节点中的特征点数目是否大于1
                    if(n1.vKeys.size()>1)
                    {
			//如果有超过一个的特征点,那么“待展开的节点计数++”
                        nToExpand++;

			//保存这个特征点数目和节点指针的信息
                        vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));

			//?这个访问用的句柄貌似并没有用到?
                        // lNodes.front().lit 和前面的迭代的lit 不同,只是名字相同而已
                        // lNodes.front().lit是node结构体里的一个指针用来记录节点的位置
                        // 迭代的lit 是while循环里作者命名的遍历的指针名称
                        lNodes.front().lit = lNodes.begin();
                    }
                }
                //后面的操作都是相同的,这里不再赘述
                if(n2.vKeys.size()>0)
                {
                    lNodes.push_front(n2);
                    if(n2.vKeys.size()>1)
                    {
                        nToExpand++;
                        vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
                        lNodes.front().lit = lNodes.begin();
                    }
                }
                if(n3.vKeys.size()>0)
                {
                    lNodes.push_front(n3);
                    if(n3.vKeys.size()>1)
                    {
                        nToExpand++;
                        vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
                        lNodes.front().lit = lNodes.begin();
                    }
                }
                if(n4.vKeys.size()>0)
                {
                    lNodes.push_front(n4);
                    if(n4.vKeys.size()>1)
                    {
                        nToExpand++;
                        vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
                        lNodes.front().lit = lNodes.begin();
                    }
                }

              //当这个母节点expand之后就从列表中删除它了,能够进行分裂操作说明至少有一个子节点的区域中特征点的数量是>1的
              //? 分裂方式是后加的先分裂,先加的后分裂。
                lit=lNodes.erase(lit);

		//继续下一次循环,其实这里加不加这句话的作用都是一样的
                continue;
            }//判断当前遍历到的节点中是否有超过一个的特征点
        }//遍历列表中的所有提取器节点

        // Finish if there are more nodes than required features or all nodes contain just one point
        //停止这个过程的条件有两个,满足其中一个即可:
        //1、当前的节点数已经超过了要求的特征点数
        //2、当前所有的节点中都只包含一个特征点

        if((int)lNodes.size()>=N 				//判断是否超过了要求的特征点数
			|| (int)lNodes.size()==prevSize)	
//prevSize中保存的是分裂之前的节点个数,如果分裂之前和分裂之后的总节点个数一样,说明当前所有的
//节点区域中只有一个特征点,已经不能够再细分了
        {
	   //停止标志置位
            bFinish = true;
        }

        // Step 6 当再划分之后所有的Node数大于要求数目时,就慢慢划分直到使其刚刚达到或者超过要求的特征点个数
        //可以展开的子节点个数nToExpand x3,是因为一分四之后,会删除原来的主节点,所以乘以3
        /**
		 * //?BUG 但是我觉得这里有BUG,虽然最终作者也给误打误撞、稀里糊涂地修复了
		 * 注意到,这里的nToExpand变量在前面的执行过程中是一直处于累计状态的,如果因为特征点个数太少,跳过了下面的else-if,又进行了一次上面的遍历
		 * list的操作之后,lNodes.size()增加了,但是nToExpand也增加了,尤其是在很多次操作之后,下面的表达式:
		 * ((int)lNodes.size()+nToExpand*3)>N
		 * 会很快就被满足,但是此时只进行一次对vSizeAndPointerToNode中点进行分裂的操作是肯定不够的;
		 * 理想中,作者下面的for理论上只要执行一次就能满足,不过作者所考虑的“不理想情况”应该是分裂后出现的节点所在区域可能没有特征点,因此将for
		 * 循环放在了一个while循环里面,通过再次进行for循环、再分裂一次解决这个问题。而我所考虑的“不理想情况”则是因为前面的一次对vSizeAndPointerToNode
		 * 中的特征点进行for循环不够,需要将其放在另外一个循环(也就是作者所写的while循环)中不断尝试直到达到退出条件。 
		 * */
        else if(((int)lNodes.size()+nToExpand*3)>N)
        {
			//如果再分裂一次那么数目就要超了,这里想办法尽可能使其刚刚达到或者超过要求的特征点个数时就退出
			//这里的nToExpand和vSizeAndPointerToNode不是一次循环对一次循环的关系,而是前者是累计计数,后者只保存某一个循环的
	//一直循环,直到结束标志位被置位
            while(!bFinish)
            {
		//获取当前的list中的节点个数
                prevSize = lNodes.size();

		//Prev这里是应该是保留的意思吧,保留那些还可以分裂的节点的信息, 这里是深拷贝
                vector<pair<int,ExtractorNode*> > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;

		//清空
                vSizeAndPointerToNode.clear();

                // 对需要划分的节点进行排序,对pair对的第一个元素进行排序,默认是从小到大排序
		// 优先分裂特征点多的节点,使得特征点密集的区域保留更少的特征点
           //! 注意这里的排序规则非常重要!会导致每次最后产生的特征点都不一样。建议使用 stable_sort
                sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());

		//遍历这个存储了pair对的vector,注意是从后往前遍历
                for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
                {
                    ExtractorNode n1,n2,n3,n4;
		    //对每个需要进行分裂的节点进行分裂
                    vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4);

                    // Add childs if they contain points
		    //其实这里的节点可以说是二级子节点了,执行和前面一样的操作
                    if(n1.vKeys.size()>0)
                    {
                        lNodes.push_front(n1);
                        if(n1.vKeys.size()>1)
                        {
//因为这里还有对于vSizeAndPointerToNode的操作,所以前面才会备份vSizeAndPointerToNode中的数据
			//为可能的、后续的又一次for循环做准备
                            vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
                            lNodes.front().lit = lNodes.begin();
                        }
                    }
                    if(n2.vKeys.size()>0)
                    {
                        lNodes.push_front(n2);
                        if(n2.vKeys.size()>1)
                        {
                            vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
                            lNodes.front().lit = lNodes.begin();
                        }
                    }
                    if(n3.vKeys.size()>0)
                    {
                        lNodes.push_front(n3);
                        if(n3.vKeys.size()>1)
                        {
                            vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
                            lNodes.front().lit = lNodes.begin();
                        }
                    }
                    if(n4.vKeys.size()>0)
                    {
                        lNodes.push_front(n4);
                        if(n4.vKeys.size()>1)
                        {
                            vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
                            lNodes.front().lit = lNodes.begin();
                        }
                    }

                    //删除母节点,在这里其实应该是一级子节点
                    lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit);

		//判断是是否超过了需要的特征点数?是的话就退出,不是的话就继续这个分裂过程,直到刚刚达到或者超过要求的特征点个数
	        //作者的思想其实就是这样的,再分裂了一次之后判断下一次分裂是否会超过N,如果不是那么就放心大胆地全部进行分裂(因为少了一个判断因此
		//其运算速度会稍微快一些),如果会那么就引导到这里进行最后一次分裂
                    if((int)lNodes.size()>=N)
                        break;
                }//遍历vPrevSizeAndPointerToNode并对其中指定的node进行分裂,直到刚刚达到或者超过要求的特征点个数

                //这里理想中应该是一个for循环就能够达成结束条件了,但是作者想的可能是,有些子节点所在的区域会没有特征点,因此很有可能一次for循环之后
		//的数目还是不能够满足要求,所以还是需要判断结束条件并且再来一次
                //判断是否达到了停止条件
                if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
                    bFinish = true;				
            }//一直进行不进行nToExpand累加的节点分裂过程,直到分裂后的nodes数目刚刚达到或者超过要求的特征点数目
        }//当本次分裂后达不到结束条件但是再进行一次完整的分裂之后就可以达到结束条件时
    }// 根据兴趣点分布,利用4叉树方法对图像进行划分区域

    // Retain the best point in each node
    // Step 7 保留每个区域响应值最大的一个兴趣点
    //使用这个vector来存储我们感兴趣的特征点的过滤结果
    vector<cv::KeyPoint> vResultKeys;

	//调整大小为要提取的特征点数目
    vResultKeys.reserve(nfeatures);

	//遍历这个节点列表
    for(list<ExtractorNode>::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
    {
		//得到这个节点区域中的特征点容器句柄
        vector<cv::KeyPoint> &vNodeKeys = lit->vKeys;

		//得到指向第一个特征点的指针,后面作为最大响应值对应的关键点
        cv::KeyPoint* pKP = &vNodeKeys[0];

		//用第1个关键点响应值初始化最大响应值
        float maxResponse = pKP->response;

		//开始遍历这个节点区域中的特征点容器中的特征点,注意是从1开始哟,0已经用过了
        for(size_t k=1;k<vNodeKeys.size();k++)
        {
			//更新最大响应值
            if(vNodeKeys[k].response>maxResponse)
            {
				//更新pKP指向具有最大响应值的keypoints
                pKP = &vNodeKeys[k];
                maxResponse = vNodeKeys[k].response;
            }
        }

        //将这个节点区域中的响应值最大的特征点加入最终结果容器
        vResultKeys.push_back(*pKP);
    }

    //返回最终结果容器,其中保存有分裂出来的区域中,我们最感兴趣、响应值最大的特征点
    return vResultKeys;
}

 

 参考: https://zhuanlan.zhihu.com/p/61738607

节点分裂顺序:后加的先分裂

具体理论参考:https://blog.csdn.net/hltt3838/article/details/113738304

 

子函数  ExtractorNode::DivideNode()

将提取器节点分成4个子节点,同时也完成图像区域的划分、特征点归属的划分,以及相关标志位的置位
 param[in & out] n1  提取器节点1:左上
 param[in & out] n2  提取器节点1:右上
param[in & out] n3  提取器节点1:左下
param[in & out] n4  提取器节点1:右下

提示:结合下面的图看,很容易明白!

void ExtractorNode::DivideNode(ExtractorNode &n1, 	
 ExtractorNode &n2,   ExtractorNode &n3,  ExtractorNode &n4)
{
   //得到当前提取器节点所在图像区域的一半长宽,当然结果需要取整
    const int halfX = ceil(static_cast<float>(UR.x-UL.x)/2);
    const int halfY = ceil(static_cast<float>(BR.y-UL.y)/2);

    //Define boundaries of childs
    //下面的操作大同小异,将一个图像区域再细分成为四个小图像区块
    //n1 存储左上区域的边界
    n1.UL = UL;
    n1.UR = cv::Point2i(UL.x+halfX,UL.y);
    n1.BL = cv::Point2i(UL.x,UL.y+halfY);
    n1.BR = cv::Point2i(UL.x+halfX,UL.y+halfY);
	//用来存储在该节点对应的图像网格中提取出来的特征点的vector
    n1.vKeys.reserve(vKeys.size());

    //n2 存储右上区域的边界
    n2.UL = n1.UR;
    n2.UR = UR;
    n2.BL = n1.BR;
    n2.BR = cv::Point2i(UR.x,UL.y+halfY);
    n2.vKeys.reserve(vKeys.size());

    //n3 存储左下区域的边界
    n3.UL = n1.BL;
    n3.UR = n1.BR;
    n3.BL = BL;
    n3.BR = cv::Point2i(n1.BR.x,BL.y);
    n3.vKeys.reserve(vKeys.size());

    //n4 存储右下区域的边界
    n4.UL = n3.UR;
    n4.UR = n2.BR;
    n4.BL = n3.BR;
    n4.BR = BR;
    n4.vKeys.reserve(vKeys.size());

    //Associate points to childs
    //遍历当前提取器节点的vkeys中存储的特征点
    for(size_t i=0;i<vKeys.size();i++)
    {
	//获取这个特征点对象
        const cv::KeyPoint &kp = vKeys[i];
	//判断这个特征点在当前特征点提取器节点图像的哪个区域,更严格地说是属于那个子图像区块
	//然后就将这个特征点追加到那个特征点提取器节点的vkeys中
	//NOTICE BUG REVIEW 这里也是直接进行比较的,但是特征点的坐标是在“半径扩充图像”坐标系下的,而节点区域的坐标则是在“边缘扩充图像”坐标系下的
        if(kp.pt.x<n1.UR.x)
        {
            if(kp.pt.y<n1.BR.y)
                n1.vKeys.push_back(kp);
            else
                n3.vKeys.push_back(kp);
        }
        else if(kp.pt.y<n1.BR.y)
            n2.vKeys.push_back(kp);
        else
            n4.vKeys.push_back(kp);
    }//遍历当前提取器节点的vkeys中存储的特征点

    //判断每个子特征点提取器节点所在的图像中特征点的数目(就是分配给子节点的特征点数目),然后做标记
    //这里判断是否数目等于1的目的是确定这个节点还能不能再向下进行分裂
    if(n1.vKeys.size()==1)
        n1.bNoMore = true;
    if(n2.vKeys.size()==1)
        n2.bNoMore = true;
    if(n3.vKeys.size()==1)
        n3.bNoMore = true;
    if(n4.vKeys.size()==1)
        n4.bNoMore = true;
}

 

 

2.2.2  computeOrientation()

 
   计算特征点的方向
  param[in] image                           特征点所在当前金字塔的图像
  param[in & out] keypoints       特征点向量
  param[in] umax                            每个特征点所在图像区块的每行的边界 u_max 组成的vector

static void computeOrientation(const Mat& image, vector<KeyPoint>& keypoints, const vector<int>& umax)
{
	// 遍历所有的特征点
    for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
         keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
    {
	// 调用IC_Angle 函数计算这个特征点的方向
        keypoint->angle = IC_Angle(image, 	//特征点所在的图层的图像
			 keypoint->pt, 	     //特征点在这张图像中的坐标
			 umax);		//每个特征点所在图像区块的每行的边界 u_max 组成的vector
    }
}

IC_Angle (const Mat& image, Point2f pt,  const vector<int> & u_max)

 这个函数用于计算特征点的方向,这里是返回角度作为方向。计算特征点方向是为了使得提取的特征点具有旋转不变性。
方法是灰度质心法:    以几何中心和灰度质心的连线作为该特征点方向
param[in] image          要进行操作的某层金字塔图像
param[in] pt                   当前特征点的坐标
 param[in] u_max         图像块的每一行的坐标边界 u_max
 return float                    返回特征点的角度,范围为[0,360)角度,精度为0.3°

static float IC_Angle(const Mat& image, Point2f pt,  const vector<int> & u_max)
{
	//图像的矩,前者是按照图像块的y坐标加权,后者是按照图像块的x坐标加权
    int m_01 = 0, m_10 = 0;

	//获得这个特征点所在的图像块的中心点坐标灰度值的指针center
    const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));

    // Treat the center line differently, v=0
    //这条v=0中心线的计算需要特殊对待
    //由于是中心行+若干行对,所以PATCH_SIZE应该是个奇数
    for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)
	//注意这里的center下标u可以是负的!中心水平线上的像素按x坐标(也就是u坐标)加权
        m_10 += u * center[u];

       // Go line by line in the circular patch  
       //这里的step1表示这个图像一行包含的字节总数。参考[https://blog.csdn.net/qianqing13579/article/details/45318279]
    int step = (int)image.step1();

	//注意这里是以v=0中心线为对称轴,然后对称地每成对的两行之间进行遍历,这样处理加快了计算速度
    for (int v = 1; v <= HALF_PATCH_SIZE; ++v)
    {
        // Proceed over the two lines
	//本来m_01应该是一列一列地计算的,但是由于对称以及坐标x,y正负的原因,可以一次计算两行
        int v_sum = 0;
	// 获取某行像素横坐标的最大范围,注意这里的图像块是圆形的!
        int d = u_max[v];

	//在坐标范围内挨个像素遍历,实际是一次遍历2个
        // 假设每次处理的两个点坐标,中心线下方为(x,y),中心线上方为(x,-y) 
        // 对于某次待处理的两个点:m_10 = Σ x*I(x,y) =  x*I(x,y) + x*I(x,-y) = x*(I(x,y) + I(x,-y))
        // 对于某次待处理的两个点:m_01 = Σ y*I(x,y) =  y*I(x,y) - y*I(x,-y) = y*(I(x,y) - I(x,-y))
       
       for (int u = -d; u <= d; ++u)
        {
		/得到需要进行加运算和减运算的像素灰度值
		//val_plus:在中心线下方x=u时的的像素灰度值
                //val_minus:在中心线上方x=u时的像素灰度值
            int val_plus = center[u + v*step], val_minus = center[u - v*step];

		//在v(y轴)上,2行所有像素灰度值之差
                v_sum += (val_plus - val_minus);

	        //u轴(也就是x轴)方向上用u坐标加权和(u坐标也有正负符号),相当于同时计算两行
                m_10 += u * (val_plus + val_minus);
        }
          //将这一行上的和按照y坐标加权
          m_01 += v * v_sum;
    }

    //为了加快速度还使用了fastAtan2()函数,输出为[0,360)角度,精度为0.3°
    return fastAtan2((float)m_01, (float)m_10);
}

理论部分:

始的 FAST 关键点没有方向信息,这样当图像发生旋转后, brief 描述子也会发生变化( 图像的灰度值可能发生改变 ) ,使得特征点对旋转不鲁棒 ;

解决方法: orientated FAST ,使用灰度质心法计算特征点的方向, 什么是灰度质心法?

其中 x、y为图像块中的像素在关键点坐标系中的坐标。需要知道,当图片旋转时,

图像块(方格区域)的质心在图像块中的位置并未改变 ( 质心在垂直坐标系中的坐标是变化的)。


上图表示, 在FAST关键点的基础上,进行描述子的计算时,当图像发生旋转后,图像上的随机像素对的坐标将会发生变化,

使得描述子的差异很大,非常影响后期的特征匹配。如何能够让图片发生旋转时,所选的随机像素对的坐标不发生改变呢?如下图所示:


 我们知道,ORB在进行FAST角点提取时,计算出了关键点的方向,上图左的向量OC,方向角为θ。
 

前面我们说过, 当图片发生旋转时,质心在图像块中的位置不变,因此,我们可以 将随机像素对在FAST关键点坐标系中的坐标(垂直坐标系)通过旋转θ角度,

转换为其在Oriented FAST关键点坐标系中的坐标(向量OC为x轴的坐标系) (这一步才是关键),

上图中的左图表示了坐标关系,而右图则表示,当图片旋转时,随机像素对在虚线坐标系(以向量OC为x轴坐标系)中的坐标不变,即旋转不变性。

 

2.3  函数computeDescriptor()

注意这是一个不属于任何类的全局静态函数,static修饰符限定其只能够被本文件中的函数调用
  计算某层金字塔图像上特征点的描述子
  param[in] image                    某层金字塔图像
  param[in] keypoints             特征点vector容器
  param[out] descriptors       描述子
  param[in] pattern                  计算描述子使用的固定随机点集

static void computeDescriptors(const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors,
                               const vector<Point>& pattern)
{
	//清空保存描述子信息的容器
    descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1);

	//开始遍历特征点
    for (size_t i = 0; i < keypoints.size(); i++)
        //计算这个特征点的描述子
        computeOrbDescriptor(keypoints[i], 	//要计算描述子的特征点
	image, 					//以及其图像
	 &pattern[0], 				//随机点集的首地址
	 descriptors.ptr((int)i));	        //提取出来的描述子的保存位置
}

 

 computeOrbDescriptor()
  计算ORB特征点的描述子。注意这个是全局的静态函数,只能是在本文件内被调用
 param[in] kpt            特征点对象
 param[in] img           提取出特征点的图像
 param[in] pattern   预定义好的随机采样点集
 param[out] desc     用作输出变量,保存计算好的描述子,长度为32*8bit
 

static void computeOrbDescriptor(const KeyPoint& kpt,const Mat& img, const Point* pattern,
                                 uchar* desc)
{
//得到特征点的角度,用弧度制表示。kpt.angle是角度制,范围为[0,360)度
    float angle = (float)kpt.angle*factorPI;
//然后计算这个角度的余弦值和正弦值
    float a = (float)cos(angle), b = (float)sin(angle);

//获得图像中心指针
    const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));

//获得图像的每行的字节数
    const int step = (int)img.step;

//原始的BRIEF描述子不具有方向信息,通过加入特征点的方向来计算描述子,称之为Steer BRIEF,具有较好旋转不变特性
//具体地,在计算的时候需要将这里选取的随机点点集的x轴方向旋转到特征点的方向。
//获得随机“相对点集”中某个idx所对应的点的灰度,这里旋转前坐标为(x,y), 旋转后坐标(x',y')推导:
    // x'= xcos(θ) - ysin(θ),  y'= xsin(θ) + ycos(θ)
    #define GET_VALUE(idx) center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + cvRound(pattern[idx].x*a - pattern[idx].y*b)]        
    // y'* step
    // x'
    //brief描述子由32*8位组成
    //其中每一位是来自于两个像素点灰度的直接比较,所以每比较出8bit结果,需要16个随机点,这也就是为什么pattern需要+=16的原因

    for (int i = 0; i < 32; ++i, pattern += 16)
    {
        int t0, //参与比较的一个特征点的灰度值
	t1,	//参与比较的另一个特征点的灰度值	//TODO 检查一下这里灰度值为int型???
	val;	//描述子这个字节的比较结果
		
        t0 = GET_VALUE(0); t1 = GET_VALUE(1);
        val = t0 < t1;						//描述子本字节的bit0
        t0 = GET_VALUE(2); t1 = GET_VALUE(3);
        val |= (t0 < t1) << 1;					//描述子本字节的bit1
        t0 = GET_VALUE(4); t1 = GET_VALUE(5);
        val |= (t0 < t1) << 2;					//描述子本字节的bit2
        t0 = GET_VALUE(6); t1 = GET_VALUE(7);
        val |= (t0 < t1) << 3;					//描述子本字节的bit3
        t0 = GET_VALUE(8); t1 = GET_VALUE(9);
        val |= (t0 < t1) << 4;					//描述子本字节的bit4
        t0 = GET_VALUE(10); t1 = GET_VALUE(11);
        val |= (t0 < t1) << 5;					//描述子本字节的bit5
        t0 = GET_VALUE(12); t1 = GET_VALUE(13);
        val |= (t0 < t1) << 6;					//描述子本字节的bit6
        t0 = GET_VALUE(14); t1 = GET_VALUE(15);
        val |= (t0 < t1) << 7;					//描述子本字节的bit7

        //保存当前比较的出来的描述子的这个字节
        desc[i] = (uchar)val;
    }//通过对随机点像素灰度的比较,得出BRIEF描述子,一共是32*8=256位

    //为了避免和程序中的其他部分冲突在,在使用完成之后就取消这个宏定义
    #undef GET_VALUE
}

理论:BRIEF 特征

https://blog.csdn.net/hltt3838/article/details/105912580
论文: BRIEF: Binary Robust Independent Elementary Features
BRIEF 算法的核心思想是在 关键点P的周围以一定模式选取N个点对,把这 N个点对的比较结果 组合起来作为描述子 。

为了保持踩点固定,工程上采用特殊设计的固定的 pattern  来做

 

点 v 绕 原点旋转 θ 角,得到点 v’ ,假设 v 点的坐标是 (x, y) ,那么可以推导得到 v’ 点的坐标( x’, y’)

 

 

参考:https://blog.csdn.net/hltt3838/article/details/113738304

  • 3
    点赞
  • 15
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

打赏作者

他人是一面镜子,保持谦虚的态度

你的鼓励是我最大的动力

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

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

打赏作者

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

抵扣说明:

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

余额充值