ORB-SLAM2特征检测详解

ORB-SLAM2特征检测

在这里插入图片描述

​ 在整个ORB系统中,首先就是Tracking线程,而线程的第一步就是对输入图像的预处理特征匹配特征检测。所以,我们要首要分析ORB中特征检测和匹配的方法。

​ ORB特征由关键点和描述子两部分组成。它的关键点称为“Oriented FAST”,是一种改进的FAST角点(计算了特征点的主方向),描述子在BRIEF(Binary Robust Independent Elementary Features)描述子)的基础上加入了上述方向信息,称为Steered BRIEF

1 整体分析:

1.1 ORBextractor参数获取

// 在追踪类构造函数中读取配置文件参数,获取这些参数来构建图像金字塔并提取ORB特征点
Tracking::Tracking():
{
    // 加载ORB特征点有关的参数
    int nFeatures = fSettings["ORBextractor.nFeatures"];        // 每一帧提取的特征点数
    float fScaleFactor = fSettings["ORBextractor.scaleFactor"]; // 金字塔尺度 eg 1.2
    int nLevels = fSettings["ORBextractor.nLevels"];            // 金字塔层级
    int fIniThFAST = fSettings["ORBextractor.iniThFAST"];       // FAST角点初始阈值
    int fMinThFAST = fSettings["ORBextractor.minThFAST"];       // 降低后阈值
}

1.2 ORB特征点整体计算流程

/**
 * @brief 用仿函数(重载括号运算符)方法来计算图像特征点
 *  1. 读取图像
 *  2. 计算图像金字塔
 *  3. 提取特征点
 *  4. 计算特征描述子矩阵
 * @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)
{ 
    // 1. 判断图像是否正确
    if(_image.empty())
        return;

    Mat image = _image.getMat();
    assert(image.type() == CV_8UC1 );

    // 2. 计算图像金字塔,金字塔保存到mvImagePyramid[level]
    ComputePyramid(image);

    // 3. 计算图像的特征点,并且将特征点进行均匀化。计算特征点主方向,均匀的特征点可以提高位姿计算精度
    // 存储所有的特征点,此处为二维的vector,第一维存储的是金字塔的层数,第二维存储的是那一层金字塔图像里提取的所有特征点
    vector < vector<KeyPoint> > allKeypoints;
    ComputeKeyPointsOctTree(allKeypoints);
    //ComputeKeyPointsOld(allKeypoints); //使用传统的方法提取并平均分配图像的特征点

    // 4. 创建图像描述子矩阵descriptors
    Mat descriptors;

    int nkeypoints = 0;
    // 计算所有的特征点总数nkeypoints(所有层)
    for (int level = 0; level < nlevels; ++level)
        nkeypoints += (int)allKeypoints[level].size();
    if( nkeypoints == 0 ) // 没有找到特征点
        // 调用cv::mat类的.realse方法,强制清空矩阵的引用计数,这样就可以强制释放矩阵的数据了
        _descriptors.release();
    else
    {
        // 如果图像金字塔中有特征点,那么就创建这个存储描述子的矩阵,注意这个矩阵是存储整个图像金字塔中特征点的描述子
        _descriptors.create(nkeypoints, 32, CV_8U); // nkeypoints是行数,32是列数
        descriptors = _descriptors.getMat();        // CV_8U矩阵元素的格式  32*8=256
    }                                               // getMat()获取这个描述子的矩阵信息

    _keypoints.clear();
    _keypoints.reserve(nkeypoints); // 预分配正确大小的空间

    // 因为遍历是一层一层进行的,但是描述子那个矩阵是存储整个图像金字塔中特征点的描述子,
    // 所以在这里设置了Offset变量来保存“寻址”时的偏移量,
    // 辅助进行在总描述子mat中的定位
    // 5.计算当前金字塔层的特征点对应描述子矩阵
    int offset = 0;
    for (int level = 0; level < nlevels; ++level)
    {
        vector<KeyPoint>& keypoints = allKeypoints[level];
        // 当前金字塔层的特征点数
        int nkeypointsLevel = (int)keypoints.size();

        if(nkeypointsLevel==0)
            continue;

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

        // 计算当前层描述子
        // rowRange 函数,用于提取 descriptors 矩阵中指定行的子矩阵
        Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
        // workingMat高斯模糊之后的图层图像  keypoints当前图层中的特征点集合
        // desc当前层特征点对应的描述子矩阵  pattern随机点对模板
        // 5.计算当前金字塔层的特征点对应描述子矩阵
        computeDescriptors(workingMat, keypoints, desc, pattern);

        offset += nkeypointsLevel;

        // 6. Scale keypoint coordinates坐标尺度还原
        // 对非第0层图像中的特征点的坐标恢复到第0层图像(原图像)的坐标系下
        // 得到所有层特征点在第0层里的坐标放到_keypoints里面
        // 对于第0层的图像特征点,他们的坐标就不需要再进行恢复了
        if (level != 0)
        {
            float scale = mvScaleFactor[level]; //getScale(level, firstLevel, scaleFactor);
            for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
                 keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
                keypoint->pt *= scale;
        }
        // 7. 将keypoints中内容插入到_keypoints 的末尾,完成最终的图像特征点向量
        _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
    }
}

2 Oriented FAST角点

2.1 缺点

​ FAST角点有以下几个问题:

① FAST关键点很容易扎堆出现,因此第一次遍历完图像后还需要用到非极大值抑制,在一定范围内保留响应值最大的值作为该范围内的FAST关键点。

尺度问题—图像金字塔

③ 不具有方向性—灰度质心法

2.2 实验验证

int main(int argc, char **argv)
{
    std::string datasetPath = "xxx/000000.png";
    cv::Mat img1 = cv::imread(datasetPath);
    if (img1.empty()) {
        std::cerr << "Could not read image: " << std::endl;
        return 1;
    }

    std::vector<cv::KeyPoint> vKeysCell;
    cv::FAST(img1,vKeysCell,20,true);    // vKeysCell存储角点  initialThFast初始阈值
        
    cv::Mat outputImg;// 创建一个空白图像,用于绘制关键点
    cv::drawKeypoints(img1, vKeysCell, outputImg);
    cv::imshow("Key Points", outputImg);
    cv::waitKey(0);

    return 0;
}

在这里插入图片描述

3 尺度不变性—图像金字塔

FAST角点存在尺度问题。根据上面的描述,FAST固定选取的是半径为3的圆,这个关键点和相机拍摄物体的分辨率有关。我在初始位置通过FAST-9判定是关键点,但是当相机靠近物体进行拍摄时,这个角点占用的像素数目就会变多,固定的半径为3的圆就检测不到角点了;或者当相机远离物体进行拍摄时,这个角点占用的像素数目就会变少,固定的半径为3的圆也检测不到角点。
ORB特征点使用图像金字塔来确保特征点的尺度不变性,故名为Oriented FAST角点。每往上一层,就对图像进行一个固定倍率的缩放,得到不同分辨率的图像。

在这里插入图片描述

图像金字塔每层结构

在这里插入图片描述

① 源码分析

/**
 * 构建图像金字塔,注意这里把每一层图像进行了扩展,这是为了方便图像边缘特征点的提取。但是源码中实际并没
 * 有获取扩充的图像,获取的仍是等比例缩放的原图像
 * @param image 输入原图像,这个输入图像所有像素都是有效的,也就是说都是可以在其上提取出FAST角点的
 */

void ORBextractor::ComputePyramid(cv::Mat image)
{
    for (int level = 0; level < nlevels; ++level)
    {
        float scale = mvInvScaleFactor[level];  // 1 1/s 1/s^2  构造函数中计算
        // Size对象sz  Size 是 OpenCV 中的一个类,用于表示图像的尺寸(宽度和高度)
        
        // 1. 计算原图像比例缩放
        Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
        
        // 2. 图像扩充。包括无效图像区域的大小。将图像进行“补边”,扩充区域图像不进行FAST角点检测   好像作为中介并没有太大用,因为后面一定会扩展图像
        Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
        
        // 3. 定义temp图像,它的大小为 wholeSize,类型与输入图像 image 相同  masktemp没有使用  Mat构造函数 cv::Mat(Size size, int type);
        Mat temp(wholeSize, image.type()), masktemp;
        
        // 使用 Rect 函数,从 temp 中选取有效图像区域,即去掉边界区域的部分,大小为 sz.width 和 sz.height,
        // 并将其赋值给 mvImagePyramid[level],即存储在图像金字塔中的当前层级图像。
        // 4. 从扩充图像抽取出实际的图像  为什么这里要绕来绕去最后又把按尺度缩减的图给了mvImagePyramid[level]  当然不能说直接把image给他,但为什么不把sz大小的给他,也就是说wholeSize这个中介并没有什么太大的用
        mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));

        // Compute the resized image
        if( level != 0 )
        {
            resize(mvImagePyramid[level-1], // 输入图像
                mvImagePyramid[level],  // 输出图像
                sz,                 // 输出图像的尺寸
                0,  // 水平方向上的缩放系数,留0表示自动计算
                0,  // 水平方向上的缩放系数,留0表示自动计算
                INTER_LINEAR); // 图像缩放的差值算法类型,这里的是双线性插值算法

 // 把源图像拷贝到目的图像的中央,四面填充指定的像素。图片如果已经拷贝到中间,只填充边界
 // 这样做是为了能够正确提取边界的FAST角点
 // EDGE_THRESHOLD指的这个边界的宽度,由于这个边界之外的像素不是原图像素而是算法生成出来的,所以不能够在EDGE_THRESHOLD之外提取特征点
 // 第一个参数 src 是输入图像。第二个参数 dst 是输出图像,即进行边界扩展后的图像。
 // 第三到第六个参数 top, bottom, left, right 分别表示在每个边界的上、下、左、右添加的像素数。在这段代码中,EDGE_THRESHOLD 被用于指定扩展的像素数。
 // 第七个参数 borderType 是一个整数,用于指定边界扩展的类型。在这里,BORDER_REFLECT_101 和 BORDER_ISOLATED 用于指定边界扩展的模式
            
            // 5. 扩充图像插值
            copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                           BORDER_REFLECT_101+BORDER_ISOLATED);      
                           // BORDER_REFLECT_101 表示使用镜像反射方式进行边界扩展。边界上的像素值通过沿边界反射方式获得,即像素值从边界开始反射,例如:abc|d|cba。

                           // BORDER_ISOLATED 表示边界扩展时不复制原始图像的边界值,而是将边界外的像素置为0。      
        }
        else
        {
            copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                           BORDER_REFLECT_101);            
        }
    }
	 // mvImagePyramid[level] = temp;	原代码mvImagePyramid 并未扩充
}

② 实验测试

​ 这个测试程序可以帮助理解上面的图像金字塔构建过程,上面源码中很奇怪的是,它的目的是为例扩展图像,但是最终并没有选择temp扩展图层。

cv::Sizecv::resizecv::Rectcv::copyMakeBorder函数使用方法

#include<iostream>
#include<vector>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>   // cv::resize
#include <opencv2/opencv.hpp>                   // imread

using namespace std;
using namespace cv;

std::vector<cv::Mat> ComputePyramid(cv::Mat image, const int nlevels, vector<cv::Mat> mvImagePyramid,
    vector<float> mvInvScaleFactor, const int EDGE_THRESHOLD);

int main()
{
    // 1. 参数
    int pyramid_nlevels = 4;
    double pyramid_scale = 0.5;
    std::vector<float>  mvInvScaleFactor  = { 1.0, 0.5, 0.25, 0.125 };
    int EDGE_THRESHOLD = 19;
    std::vector<cv::Mat> mvImagePyramid, PyramidShow;
    mvImagePyramid.resize(pyramid_nlevels);  // 要设置容器内图像数,否则报错
    PyramidShow.resize(pyramid_nlevels);

    // 2. 读取图像
    // 读取图像
    cv::Mat image = cv::imread("222.jpg", cv::IMREAD_COLOR);

    if (image.empty()) {
        std::cout << "Failed to read the image." << std::endl;
        return -1;
    }

    // 3.缩放图像,因为imread的图太大
    cv::Size targetSize(640, 480);
    cv::Mat resizedImage;
    cv::resize(image, resizedImage, targetSize,0,0, INTER_LINEAR); // INTER_NEAREST:最近邻插值 INTER_CUBIC:双三次插值
	
    // 4. 构建图像金字塔、扩充图像()双线性插值
    PyramidShow = ComputePyramid(resizedImage, pyramid_nlevels, mvImagePyramid,
        mvInvScaleFactor, EDGE_THRESHOLD);


    // 5.显示原始图像和缩放后的图像
    cv::namedWindow("Original Image", cv::WINDOW_AUTOSIZE);
    cv::imshow("Original Image", resizedImage);

    cv::namedWindow("s = 1", cv::WINDOW_AUTOSIZE);
    cv::imshow("s = 1", PyramidShow[0]);

    cv::namedWindow("s = 0.5", cv::WINDOW_AUTOSIZE);
    cv::imshow("s = 0.5", PyramidShow[1]);

    cv::namedWindow("s = 0.25", cv::WINDOW_AUTOSIZE);
    cv::imshow("s = 0.25", PyramidShow[2]);

    cv::namedWindow("s = 0.125", cv::WINDOW_AUTOSIZE);
    cv::imshow("s = 0.125", PyramidShow[3]);

    cv::waitKey(0);
    cv::destroyAllWindows();

    return 0;

}

std::vector<cv::Mat>  ComputePyramid(cv::Mat image,const int nlevels,vector<cv::Mat> mvImagePyramid,
                                    vector<float> mvInvScaleFactor, const int EDGE_THRESHOLD)
{
    for (int level = 0; level < nlevels; ++level)
    {
        float scale = mvInvScaleFactor[level];  

        cv::Size sz(cvRound((float)image.cols * scale), cvRound((float)image.rows * scale));

        cv::Size wholeSize(sz.width + EDGE_THRESHOLD * 2, sz.height + EDGE_THRESHOLD * 2);
        // 扩充图像
        cv::Mat temp(wholeSize, image.type());
        // 使用 Rect 函数,从 temp 中选取有效图像区域,即去掉边界区域的部分,大小为 sz.width 和 sz.height,
        // 并将其赋值给 mvImagePyramid[level],即存储在图像金字塔中的当前层级图像。
        // cv::Rect(int x, int y, int width, int height):根据指定的位置和大小创建一个矩形。
        mvImagePyramid[level] = temp(cv::Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));


        if (level != 0)
        {
            cv::resize(image, mvImagePyramid[level],  sz, 0, 0, INTER_LINEAR);      
            // 将图像扩充部分插值
            cv::copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                BORDER_REFLECT_101 + BORDER_ISOLATED);     
        }
        else
        {
            cv::resize(image, mvImagePyramid[level], sz, 0, 0, INTER_LINEAR);
            cv::copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                BORDER_REFLECT_101);
        }
        mvImagePyramid[level] = temp;
    }
    return mvImagePyramid;
}

​ 以原始图像大小为例,它会对每层图像进行EDGE_THRESHOLD * 2的扩展,所以右图比左图大。

在这里插入图片描述

​ 很明显可以看出来,右图经过插值填充了EDGE_THRESHOLD 区域,所以看起来很奇怪。但这是为了服务特征点的提取,并不会用到这些点。

在这里插入图片描述

③ 关于这部分代码问题

cv::Size wholeSize(sz.width + EDGE_THRESHOLD * 2, sz.height + EDGE_THRESHOLD * 2);这个作为中间值其实是没有用的,可以直接跳过

void ORBextractor::ComputePyramid(cv::Mat image)
{

    for (int level = 0; level < nlevels; ++level)
    {
        float scale = mvInvscaleFactor[level];  
        // Size对象sz  Size 是 OpenCV 中的一个类,用于表示图像的尺寸(宽度和高度)
        
        // 1. 计算原图像比例缩放
        cv::Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
        
        // 2. 定义temp图像,它的大小为 sz,类型与输入图像 image 相同       Mat构造函数 cv::Mat(Size size, int type);
        cv::Mat temp(sz, image.type());

        mvImagePyramid[level] = temp;

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

            // 3. 扩充图像插值
            cv::copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,cv::BORDER_REFLECT_101+cv::BORDER_ISOLATED);                             		}
        else
        {
            cv::copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                           cv::BORDER_REFLECT_101);            
        }
        mvImagePyramid[level] = temp;	// 源代码这里并没有使用扩展的temp
    }


}


// 调用测试  效果一样
int main(int argc, char **argv)
{

    ORBextractor test(1000,8,20,7,1.2);
    std::string datasetPath = "/home/wheeltec-client/xxx/slam_data/000000.png";
    cv::Mat img1 = cv::imread(datasetPath);
    if (img1.empty()) {
        std::cerr << "Could not read image: " << std::endl;
        return 1;
    }
    test.ComputePyramid(img1);
    cv::imshow("img1",img1);
    cv::Mat img2 = test.GetmvImagePyramid()[0];	
    cv::imshow("img2",img2);
    cv::waitKey(0);
    return 0;
}

在这里插入图片描述

④ 关于opencv图像扩充方法对比

在这里插入图片描述

4 旋转不变性—灰度质心法

① 原理推导

​ 以关键点为中心选择一个圆形区域,特征点坐标(整数)是几何中心,即形心。然后计算关键点的”主方向“,这里的主方向即由形心指向质心的向量。这里计算的 θ \theta θ,将旋转描述子所旋转的所有点对,统一将像素旋转到这个“主方向”,这就引入了旋转不变性。

​ 下面介绍灰度质心法的步骤:

​ 定义圆心区域图像的矩
m p q = ∑ x , y x p y q I ( x , y ) , p , q = { 0 , 1 } m_{pq}=\sum_{x,y}x^{p}y^{q}I(x,y),\quad p,q=\{0,1\} mpq=x,yxpyqI(x,y),p,q={0,1}
​ 在半径为 R R R的圆形图像区域,沿两个坐标轴 x , y x,y x,y方向的图像矩分别为
m 10 = ∑ x = − R R ∑ y = − R R x I ( x , y ) m 01 = ∑ x = − R R ∑ y = − R R y I ( x , y ) \begin{gathered} m_{10} =\sum_{x=-R}^R\sum_{y=-R}^RxI(x,y) \\ m_{01} =\sum_{x=-R}^{R}\sum_{y=-R}^{R}yI(x,y) \end{gathered} m10=x=RRy=RRxI(x,y)m01=x=RRy=RRyI(x,y)
圆形区域内所有像素的灰度值总和为:
m 00 = ∑ x = − R R ∑ y = − R R I ( x , y ) m_{00}=\sum_{x=-R}^{R}\sum_{y=-R}^{R}I(x,y) m00=x=RRy=RRI(x,y)
图像的质心为:
C = ( c x , c y ) = ( m 10 m 00 , m 01 m 00 ) C=(c_{x},c_{y})=\left(\frac{m_{10}}{m_{00}},\frac{m_{01}}{m_{00}}\right) C=(cx,cy)=(m00m10,m00m01)
​ 于是关键点的旋转角度记为
θ = arctan ⁡ 2 ( c y , c x ) = arctan ⁡ 2 ( m 01 , m 10 ) \theta=\arctan2\left(c_{y},c_{x}\right)=\arctan2\left(m_{01},m_{10}\right) θ=arctan2(cy,cx)=arctan2(m01,m10)

② 获取角度 θ θ θ程序

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)
    {
        keypoint->angle = IC_Angle(image, keypoint->pt, umax);  // 每个关键点主方向
    }
}

③ 计算角度 θ θ θ程序

​ 注意,十四讲中采用的是矩形框,真正的ORB算法采用的是圆形。它的质心计算使用到了一定的技巧。
在这里插入图片描述

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

// 这里是static全局函数,因为这个函数没有写到特征提取类中
static float IC_Angle(const Mat& image, Point2f pt,  const vector<int> & u_max)
{
    int m_01 = 0, m_10 = 0;
	
    //cvRound表示取整,以关键点像素地址为center指针
    const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));  

    // 1.单独求圆形区域水平坐标轴这一行像素灰度,这一行y=0,所以只需要计算m10=x*I(x,y)
    // 	 HALF_PATCH_SIZE = 15 = 圆半径 奇数 = 2*数+1
    for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)
        m_10 += u * center[u];

    // 2.对称计算每一行的m10和m01,m10=x(I(X,Y)+I(x,-y))   m01=y(I(X,Y)-I(x,-y))
    int step = (int)image.step1();  // 图像一行的字节数
    for (int v = 1; v <= HALF_PATCH_SIZE; ++v) // 计算15次(行row)
    {
        // Proceed over the two lines
        int v_sum = 0;
        int d = u_max[v];	// 得到这一行的区域最大x坐标范围d(半径)
        for (int u = -d; u <= d; ++u)
        {
            //3. 利用指针计算像素强度I(x,y)  以pt.x,pt.y为中心,列坐标+行数*行字节数 非常巧妙
            int val_plus = center[u + v*step], val_minus = center[u - v*step];
            v_sum += (val_plus - val_minus);  
            m_10 += u * (val_plus + val_minus);  
        }
        m_01 += v * v_sum;
    }

    return fastAtan2((float)m_01, (float)m_10);  // arctan
}

④ 验证

/* 这里分析了灰度质心法的计算、以及umax的计算
1. 求取质心m00,形心以一个随机的特征点表示
2. 注意质心坐标,它的计算值是相对与形心(0,0)的,所以在不能直接作为图像中的坐标!
3. 这里的半径R设置很大,因为半径小了看不清结果
4. 这里只画了一个特征点,后续可以拓展画出所有的特征点
*/
#include<iostream>
#include<vector>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>   // cv::resize
#include <opencv2/opencv.hpp>                   // imread

using namespace std;
using namespace cv;


vector<int> compute_umax(const int R);
cv::Point2f IC_Angle(const Mat& image, Point2f pt, const vector<int>& u_max,
    const int HALF_PATCH_SIZE);

int main()
{
    // 1. 参数设置  
	int R = 200;   
    // 2. 读取图像
    cv::Mat image = cv::imread("222.jpg", 1);  // 注意要读取的是灰度图,IC_Angle中是uchar

    if (image.empty()) {
        std::cout << "Failed to read the image." << std::endl;
        return -1;
    }
    // 3.缩放图像,因为imread的图太大
    cv::Size targetSize(1280, 720);
    cv::Mat resizedImage;
    cv::resize(image, resizedImage, targetSize, 0, 0, INTER_LINEAR);

    // key points, using GFTT here.
    vector<KeyPoint> kp;
    Ptr<GFTTDetector> detector = GFTTDetector::create(500, 0.01, 20); // 最多500 keypoints
    detector->detect(resizedImage, kp);
    cv::Point2f keypoint(kp[15].pt.x, kp[15].pt.y);

     画出关键点
    //cv::Mat kpimg;
    //cv::drawKeypoints(resizedImage, kp, kpimg, Scalar::all(-1), DrawMatchesFlags::DEFAULT);
    //cv::imshow("ORB features", kpimg);

    // 4.计算角度
    float angle = 0, m01 = 0, m10 = 0;
    cv::Point2f centroid = IC_Angle(resizedImage, keypoint, compute_umax(R), R);

    // 5. 
    cv::circle(resizedImage, keypoint, 5, cv::Scalar(0, 0, 255), -1); // 用红色实心圆画出第一个点
    cv::circle(resizedImage, centroid, 5, cv::Scalar(0, 0, 255), -1); // 用红色实心圆画出第二个点
    cv::line(resizedImage, keypoint, centroid, cv::Scalar(0, 255, 0), 2); // 用绿色线段连接两个点
    //cv::circle(resizedImage, keypoint, 10, cv::Scalar(0, 0, 255), -1); // 用红色实心圆画出第一个点
    //cv::circle(resizedImage, centroid, 10, cv::Scalar(0, 0, 255), -1); // 用红色实心圆画出第二个点
    //cv::line(resizedImage, keypoint, centroid, cv::Scalar(0, 255, 0), 2); // 用绿色线段连接两个点

    cv::imshow("Image", resizedImage);
    cv::waitKey(0);

}


vector<int> compute_umax(const int R)
{
    vector<int> umax;
    int v, v0, vmax = cvFloor(R * sqrt(2.f) / 2 + 1); // 向下取整
    int vmin = cvCeil(R * sqrt(2.f) / 2);  // 向上取整
  
    umax.resize(R + 1);
    const double hp2 = R * R;  // R^2
    for (v = 0; v <= vmax; ++v)
    {
        umax[v] = cvRound(sqrt(hp2 - v * v));   // 四舍五入取整
        //cout << umax[v] << ' ';
    }

    for (v = R, v0 = 0; v >= vmin; --v)
    {
        while (umax[v0] == umax[v0 + 1])
            ++v0;
        umax[v] = v0;
        ++v0;
    }
    cout << endl;
    for (auto& k : umax)
    {
        //cout << k << ' ';
    }
    return umax;
}



Point2f IC_Angle(const Mat& image, Point2f pt, const vector<int>& u_max,
                                  const int HALF_PATCH_SIZE)
{
    int m_01 = 0, m_10 = 0, m_00 = 0;

    //cvRound表示取整,以关键点像素地址为center指针
    const uchar* center = &image.at<uchar>(cvRound(pt.y), cvRound(pt.x));

    // 1.单独求圆形区域水平坐标轴这一行像素灰度,这一行y=0,所以只需要计算m10=x*I(x,y)
    // 	 HALF_PATCH_SIZE = 15 = 圆半径 奇数 = 2*数+1
    for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)
    {
        m_10 += u *center[u];
        m_00 += center[u];
    }

    // 2.对称计算每一行的m10和m01,m10=x(I(X,Y)+I(x,-y))   m01=y(I(X,Y)-I(x,-y))  m00 = I(X,Y)+I(x,-y)
    int step = (int)image.step1();  // 图像一行的字节数
    for (int v = 1; v <= HALF_PATCH_SIZE; ++v) // 计算15次(行row)
    {
        // Proceed over the two lines
        int v_sum = 0;
        int d = u_max[v];	// 得到这一行的区域最大x坐标范围d(半径)
        for (int u = -d; u <= d; ++u)
        {
            //3. 利用指针计算像素强度I(x,y)  以pt.x,pt.y为中心,列坐标+行数*行字节数 非常巧妙
            int val_plus =center[u + v * step], val_minus = center[u - v * step];
            v_sum += (val_plus - val_minus);
            m_10 += u * (val_plus + val_minus);
            m_00 += val_plus + val_minus;
        }
        m_01 += v * v_sum;
    }
    // 5. 画出形心和质心
    float C1 = float(m_10) / m_00 + pt.x;
    float C2 = float(m_01) / m_00 + pt.y; 
    cv::Point2f centroid(C1, C2);
    return centroid;  
}

结果

在这里插入图片描述

5 旋转不变性—Steered BRIEF

① 原理分析

​ 确定了关键点,就要对每个关键点的信息进行量化,计算其描述子。ORB特征点中的描述子是在BRIEF的基础上进行改进的,称为Steered BRIEF
BRIEF是一种二进制编码的描述子,在ORB-SLAM2中它是一个256 bit的向量,其中每个bit是0或1。这样我们在比较两个描述子时,可以直接用异或位运算计算汉明距离,速度非常快。
步骤

为减少噪声干扰,先对图像进行高斯滤波

以关键点为中心,取一定大小的图像窗口P。在窗口内随机选取一对点,比较二者像素的大小,进行如下二进制赋值
τ ( p ; x , y ) : = { 1 : p ( x ) < p ( y ) 0 : p ( x ) ⩾ p ( y ) \tau(p;x,y):=\begin{cases}1&:p(x)<p(y)\\0&:p(x)\geqslant p(y)\end{cases} τ(p;x,y):={10:p(x)<p(y):p(x)p(y)
​ 实际上,在ORB-SLAM中,其采用了固定选点模板。

③ 在窗口中随机选取N(在ORB-SLAM2中N=256)对随机点,重复第2步的二进制赋值,最后得到一个256维的二进制描述子。

补充:二维平面的旋转可以看作是绕Z轴(固定轴)旋转的结果,只取平面 x o y xoy xoy的结果,可以写为如下的矩阵形式。也可以从下面的图中直接推出来。
[ x ′ y ′ ] = [ cos ⁡ θ − sin ⁡ θ sin ⁡ θ cos ⁡ θ ] [ x y ] \begin{bmatrix}x'\\y'\end{bmatrix}=\begin{bmatrix}\cos\theta&-\sin\theta\\\sin\theta&\cos\theta\end{bmatrix}\begin{bmatrix}x\\y\end{bmatrix} [xy]=[cosθsinθsinθcosθ][xy]
在这里插入图片描述

② 源码分析

//注意这是一个不属于任何类的全局静态函数,static修饰符限定其只能够被本文件中的函数调用
/**
 * @brief 计算某层金字塔图像上特征点的描述子
 * 
 * @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); // 行维=关键点总数  列维=32 矩阵元素都是CV_8UC1 8位  32*8=256

    for (size_t i = 0; i < keypoints.size(); i++)
        computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i));  //  ptr函数,用于获取 descriptors 矩阵中指定行的指针
}



/**
 * @brief 计算ORB特征点的描述子。注意这个是全局的静态函数,只能是在本文件内被调用
 * @param[in] kpt       特征点对象
 * @param[in] img       提取特征点的图像
 * @param[in] pattern   预定义好的采样模板
 * @param[out] desc     用作输出变量,保存计算好的描述子,维度为32*8 = 256 bit
 */
const float factorPI = (float)(CV_PI/180.f);  // 角度转弧度
static void computeOrbDescriptor(const KeyPoint& kpt,
                                 const Mat& img, const Point* pattern,
                                 uchar* desc)
{
    float angle = (float)kpt.angle*factorPI;
    float a = (float)cos(angle), b = (float)sin(angle);  // cos(Θ),sin(Θ)

    const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
    const int step = (int)img.step;
	
    // 旋转随机点对到主方向   \ 用作行续符号  宏定义GET_VALUE
    #define GET_VALUE(idx) \
        center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
               cvRound(pattern[idx].x*a - pattern[idx].y*b)]


    for (int i = 0; i < 32; ++i, pattern += 16)
    {
        int t0, t1, val;
        t0 = GET_VALUE(0); t1 = GET_VALUE(1);
        val = t0 < t1;
        t0 = GET_VALUE(2); t1 = GET_VALUE(3);	// <<优先级高于|
        val |= (t0 < t1) << 1;  //  << 1 是将条件表达式的结果左移一位 |= 是按位或赋值运算符
        t0 = GET_VALUE(4); t1 = GET_VALUE(5);
        val |= (t0 < t1) << 2;
        t0 = GET_VALUE(6); t1 = GET_VALUE(7);
        val |= (t0 < t1) << 3;
        t0 = GET_VALUE(8); t1 = GET_VALUE(9);
        val |= (t0 < t1) << 4;
        t0 = GET_VALUE(10); t1 = GET_VALUE(11);
        val |= (t0 < t1) << 5;
        t0 = GET_VALUE(12); t1 = GET_VALUE(13);
        val |= (t0 < t1) << 6;
        t0 = GET_VALUE(14); t1 = GET_VALUE(15);
        val |= (t0 < t1) << 7;

        desc[i] = (uchar)val; // 8位描述子,一共16个点  16*32=512=256*2个点
    }

    #undef GET_VALUE  // 取消宏定义
}

// ORB预定义的特殊点对
static int bit_pattern_31_[256*4] =
{
    8,-3, 9,5/*mean (0), correlation (0)*/,
    4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/,
    -11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/,
};    

③ 旋转随机点对本质

​ 如图所示,我们把上面的随机点对全部旋转到“主方向”,也就是把整个坐标系旋转至“主方向”(从z轴视角来看)。其中点P是特征点位置,也就是几何中心;点Q是圆形区域质心。

在这里插入图片描述

6 均匀化策略

​ 为了避免特征点过于集中,ORB-SLAM中采用了均匀化策略来提高精度,如位姿计算,避免冗余。

在这里插入图片描述

6.1 第一步:计算每一层金字塔特征点数、umax

(1)原理分析

​ 根据总的图像金字塔层级数 m m m和待提取的特征点总数 N N N,计算图像金字塔中每个层级需要提取的特征点数量。第 0 0 0层图像的宽为 W W W,高为 H H H,对应的面积 H W = C HW=C HW=C,图像金字塔缩放因子为 s s s, 0 < s < 1 0<s<1 0<s<1
1. 计算所有层级的总面积
S = H W ( s 2 ) 0 + H W ( s 2 ) 1 + ⋯ + H W ( s 2 ) ( m − 1 ) = H W 1 − ( s 2 ) m 1 − s 2 = C 1 − ( s 2 ) m 1 − s 2 \begin{aligned}S&=HW(s^2)^0+HW(s^2)^1+\cdots+HW(s^2)^{(m-1)}\\&=HW\frac{1-(s^2)^m}{1-s^2}=C\frac{1-(s^2)^m}{1-s^2}\end{aligned} S=HW(s2)0+HW(s2)1++HW(s2)(m1)=HW1s21(s2)m=C1s21(s2)m
2. 单位面积被分配的特征点数量为
N a v g = N S = N C 1 − ( s 2 ) m 1 − s 2 = N ( 1 − s 2 ) C [ 1 − ( s 2 ) m ] N_{\mathrm{avg}}=\frac{N}{S}=\frac{N}{C\frac{1-(s^2)^m}{1-s^2}}=\frac{N(1-s^2)}{C[1-(s^2)^m]} Navg=SN=C1s21(s2)mN=C[1(s2)m]N(1s2)
3. 原图像即第0层分配特征点数量
N 0 = C N a v g = N ( 1 − s 2 ) 1 − ( s 2 ) m N_0=CN_{\mathrm{avg}}=\frac{N(1-s^2)}{1-(s^2)^m} N0=CNavg=1(s2)mN(1s2)
4. 第 i i i层金字塔分配特征点数量
N i = N ( 1 − s 2 ) C [ 1 − ( s 2 ) m ] C ( s 2 ) i = N ( 1 − s 2 ) 1 − ( s 2 ) m ( s 2 ) i N_i=\frac{N(1-s^2)}{C[1-(s^2)^m]}C(s^2)^i=\frac{N(1-s^2)}{1-(s^2)^m}(s^2)^i Ni=C[1(s2)m]N(1s2)C(s2)i=1(s2)mN(1s2)(s2)i
5. ORB-SLAM中实际以s即面积开方来平均特征点
N i = N ( 1 − s ) C [ 1 − ( s ) m ] C ( s ) i = N ( 1 − s ) 1 − ( s ) m ( s ) i N_i=\frac{N(1-s)}{C[1-(s)^m]}C(s)^i=\frac{N(1-s)}{1-(s)^m}(s)^i Ni=C[1(s)m]N(1s)C(s)i=1(s)mN(1s)(s)i

(2)源码分析

​ 上面这一过程在ORBextractor类构造函数中初始化完成,下面具体分析

/**
 * @brief ORBextractor类构造函数,初始化参数,计算每层金字塔的特征点数,计算灰度质心法中的圆形区域
 *		  不同行的列范围umax
 * 
 * @param[in & out]  _nfeatures  提取器节点1:要提取的总特征点数
 * @param[in & out] _scaleFactor 1/s
 * @param[in & out] _nlevels	 金字塔层数
 * @param[in & out] _iniThFAST   初始FAST角点可信阈值
 * @param[in & out] _minThFAST   指FAST角点最低可信阈值(均匀化策略,降低选取标准)
 */

ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels,
         int _iniThFAST, int _minThFAST):
    nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
    iniThFAST(_iniThFAST), minThFAST(_minThFAST)
{ 
    mvScaleFactor.resize(nlevels);  // 1 1/s 1/s^2  1/s^3 ...
    mvLevelSigma2.resize(nlevels);  // 1 1/s^2 1/s^4 ....
    mvScaleFactor[0]=1.0f;
    mvLevelSigma2[0]=1.0f;
    for(int i=1; i<nlevels; i++)
    {
        mvScaleFactor[i]=mvScaleFactor[i-1]*scaleFactor;
        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]; // // 1 s s^2
        mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
    }

    mvImagePyramid.resize(nlevels);  // std::vector<cv::Mat> mvImagePyramid;  对应不同的金字塔层图像

    mnFeaturesPerLevel.resize(nlevels);
    float factor = 1.0f / scaleFactor;      // s
    // N0 = N(1-s)/(1-s^m)
    float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));  

    int sumFeatures = 0;
    for( int level = 0; level < nlevels-1; level++ )
    {	// Ni = (N(1-s)/(1-s^m))s^i
        mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
        sumFeatures += mnFeaturesPerLevel[level];
        nDesiredFeaturesPerScale *= factor;
    }
    mnFeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);  // 最顶层金字塔图像特征点数

    const int npoints = 512;    // 256点对,即512个点
    const Point* pattern0 = (const Point*)bit_pattern_31_;  // int bit_pattern_31_[256*4] 
    // 强制把整型数组指针bit_pattern_31_(数组首地址)转换为Point型,然后赋给Point型指针pattern0
    std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
    // 类成员定义std::vector<cv::Point> pattern;
    // 将从范围 [pattern0, pattern0 + npoints) 中的元素复制到 pattern 容器中,pattern数组指针
    // 在计算描述子时使用,每次迭代16个点,8对,8位uchar
    // std::back_inserter(pattern) 是一个迭代器,它在 pattern 容器的末尾插入元素


    // 计算化灰度质心法中圆的每一行最大半径  v是行索引,从0-R之间每一行最大的半径 
    umax.resize(HALF_PATCH_SIZE + 1);   //  std::vector<int> umax; 
    // 1. 计算0-vmax
    int v, v0, vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.f) / 2 + 1); // 向下取整
    int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.f) / 2);  // 向上取整
    // 除HALF_PATCH_SIZE * sqrt(2.f) / 2是整数外,vmin=vmax
    const double hp2 = HALF_PATCH_SIZE*HALF_PATCH_SIZE;  // R^2
    for (v = 0; v <= vmax; ++v)
        umax[v] = cvRound(sqrt(hp2 - v * v));   // 四舍五入取整
    // 2.计算vmin(=vmax)-R
    // Make sure we are symmetric均匀对称
    for (v = HALF_PATCH_SIZE, v0 = 0; v >= vmin; --v)
    {
        while (umax[v0] == umax[v0 + 1])
            ++v0;
        umax[v] = v0;
        ++v0;
    }
}

(3)umax推导

​ 这里较难理解的是umax的计算。

HALF_PATCH_SIZE就是半径Ru是列坐标,v是行坐标。以 45 ° 45° 45°为区分线,按代码中两步分别计算。 R 2 = u 2 + v 2 R^2 = u^2 + v^2 R2=u2+v2. 代码中 v m i n 、 v m a x vmin、vmax vminvmax差不多为 R / 根号 2 R/根号2 R/根号2 45 ° 45° 45°处,下面的计算和上面的计算是对称的,但实际中因为取整的关系,并不是完全的对称。在1.2.4中也单独验证了该算法,最好debug调试查看

在这里插入图片描述

R=15时候的umax

在这里插入图片描述

6.2 第二步:划分格子,遍历提取每一个格子中的FAST角点

划分格子,在 O R B − S L A M 2 ORB-SLAM2 ORBSLAM2中格子固定尺寸为 30 30 30像素 × 30 ×30 ×30像素。依次在每一个格子中提取 F A S T FAST FAST角点(直接调用opencv库)。如果初始的 F A S T FAST FAST角点阈值没有检测到角点,则降低 F A S T FAST FAST角点阈值,这样在弱纹理区域也能提取到更多的角点。如果降低一次阈值后还是提取不到角点,则不在这个格子里提取,这样可以避免提取到质量特别差的角点。

(1)图像边界、格子

​ 关于这里的边界问题,首先图像时扩充过的,上下左右四个方向都扩充了19个像素。minBorder是选择减去上下左右16个像素的图像边界,这里减3是因为在计算FAST特征点的时候,需要建立一个半径为3的圆。保证原始图像边界点的正确检测。程序中因为取整的原因,并不一定是30*30(相近),这里以30*30分析。

const float iniY =minBorderY+i*hCell; // 第i个方格子占的像素行数hCell
float maxY = iniY+hCell+6; // 加6即3+30+3  都是为了保证边界像素进行FAST特征点提取
// 然后还有一点值的注意,就是最后一个cell可能就没有30左右,有多大取多大

在这里插入图片描述
在这里插入图片描述

(2)源码分析

void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint> >& allKeypoints)
{
    // 重新调整图像层数
    allKeypoints.resize(nlevels);

    // 图像网格块cell的尺寸,是个正方形
    const float W = 30;

    for (int level = 0; level < nlevels; ++level)
    {   
        // 1. 计算边界
        // EDGE_THRESHOLD = 19  在构建金字塔时图像进行了扩充
        // 这里的3是因为在计算FAST特征点的时候,需要建立一个半径为3的圆
        const int minBorderX = EDGE_THRESHOLD-3;  // 16  
        const int minBorderY = minBorderX; // 16 std::vector<cv::Mat> mvImagePyramid;
        const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
        const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;

        // 存储需要进行平均分配的特征点
        vector<cv::KeyPoint> vToDistributeKeys;
        vToDistributeKeys.reserve(nfeatures*10); // 10倍总特征点数

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

        const int nCols = width/W;  // 列方向有多少图像网格块(30*30)
        const int nRows = height/W; // 行方向有多少图像网格块(30*30)
        // 计算每个图像网格块所占的像素行数和列数
        const int wCell = ceil(width/nCols);
        const int hCell = ceil(height/nRows);

        // 2. 开始遍历图像网格(30*30),以行开始遍历的(从第一列的行)
        for(int i=0; i<nRows; i++)
        {
            // 行方向第i个图像网格块
            // 计算当前网格最大的行坐标,这里的+6=+3+3,即考虑到了多出来3是为了cell边界像素进行FAST特征点提取用
            // 前面的EDGE_THRESHOLD指的应该是提取后的特征点所在的边界,所以minBorderY是考虑了计算半径时候的图像边界
            const float iniY =minBorderY+i*hCell;
            float maxY = iniY+hCell+6;

            if(iniY>=maxBorderY-3)
                continue;
            if(maxY>maxBorderY)
                maxY = maxBorderY;

            // 3. 开始列的遍历
            for(int j=0; j<nCols; j++)
            {
                const float iniX =minBorderX+j*wCell;
                float maxX = iniX+wCell+6;
                if(iniX>=maxBorderX-6)
                    continue;
                if(maxX>maxBorderX)
                    maxX = maxBorderX;

                // 4. FAST提取兴趣点, 自适应阈值
                // 这个向量存储这个cell中的特征点
                vector<cv::KeyPoint> vKeysCell;
                FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), // 图像块区域
                    // vKeysCell存储角点  iniThFAST初始阈值
                     vKeysCell,iniThFAST,true); // true表示使能非极大值抑制,避免角过于集中

                // 5. 如果这个图像块中使用默认的FAST检测阈值没有能够检测到角点
                if(vKeysCell.empty())
                {
                    // 使用更低的阈值minThFAST来进行重新检测
                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                         vKeysCell,minThFAST,true); // true表示使能非极大值抑制,避免特征点过于集中
                }

                if(!vKeysCell.empty())
                {  // 6. 遍历其中的所有FAST角点,恢复其在整个金字塔当前层图像下的坐标
                 // 因为这里提取的特征点的坐标只是小方块30*30的坐标,恢复特征点在当前金字塔层的坐标
                    for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
                    {
                        (*vit).pt.x+=j*wCell;
                        (*vit).pt.y+=i*hCell;
                        vToDistributeKeys.push_back(*vit);
                    }
                }

            }
        }

        //  声明一个对当前图层的特征点的容器的引用
        vector<KeyPoint> & keypoints = allKeypoints[level];
        keypoints.reserve(nfeatures);

        // 7. 利用四叉树均匀选取当前金字塔层特征点。   vToDistributeKeys是当前层提取的角点
        // mnFeaturesPerLevel[level]是当前层分配的特征点数目   level当前层级
        keypoints = DistributeOctTree(vToDistributeKeys, 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++)
        {
            // 8.对每一个保留下来的特征点,恢复到相对于当前图层“边缘扩充图像下”的坐标系的坐标
            // 因为现在是在排除上下左右都为16的区域进行的特征提取
            keypoints[i].pt.x+=minBorderX;
            keypoints[i].pt.y+=minBorderY;
            // 记录特征点来源的图像金字塔图层
            keypoints[i].octave=level;
            // 记录计算方向的patch,缩放后对应的大小,又被称作为特征点半径
            keypoints[i].size = scaledPatchSize;
        }
    }

    // 9.计算每一层每一个特征点的主方向
    for (int level = 0; level < nlevels; ++level)
        computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
}

6.3 第三步:四叉树

6.3.1节点分裂算法

​ 节点第 1 1 1次分裂, 1 1 1个根节点分裂为 4 4 4个子节点。分裂之后根据图像的尺寸划分节点的区域,对应的边界为 U L i , U R i , B L i , B R i , i = 1 , 2 , 3 , 4 UL_i,UR_i,BL_i,BR_i,i=1,2,3,4 ULi,URi,BLi,BRi,i=1,2,3,4分别对应左上角、右上角、左下角、右下角 4 4 4个坐标。有些坐标会被多个节点共享,比如图像中心点坐标就同时被 B R 1 , B L 2 , U R 3 , U L 44 BR1,BL2,UR3,UL44 BR1,BL2,UR3,UL44个点共享。落在某个节点区域范围内的所有特征点都属于该节点的元素

在这里插入图片描述

​ 这里需要注意的是,一个母节点分裂为 4 4 4个子节点后,需要在节点链表中删掉原来的母节点,所以实际上一次分裂净增加了 3 3 3个节点。因此,下次分裂后,节点的总数是可以提前预估的,计算方式为:当前节点总数十即将分裂的 节点总数 × 3 节点总数×3 节点总数×3。下次分裂最多可以得到 4 + 4 × 3 = 16 4+4×3=16 4+4×3=16个节点

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

class ExtractorNode  // 定义划分节点类
{
public:
    ExtractorNode():bNoMore(false){}  // 构造函数,初始化列表参数
	//
    void DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4);	// 分配节点函数

    std::vector<cv::KeyPoint> vKeys; // 当前母节点区域内关键点数组vector
    cv::Point2i UL, UR, BL, BR;		 // 一个矩形图像区域四个角的坐标(当前节点-母节点)
    std::list<ExtractorNode>::iterator lit;		// 构建list容器
    bool bNoMore;	// 表示属于当前节点的特征点数量=1则为true
};


void ExtractorNode::DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4)
{
    // 1.计算当前节点所在图像区域的一半长宽  ceil向上取整  static_cast强制把Point2i类型转float   
    const int halfX = ceil(static_cast<float>(UR.x-UL.x)/2);
    const int halfY = ceil(static_cast<float>(BR.y-UL.y)/2);

    
// 注意这里是记录的坐标(x,y) 但一般图像中索引是(y,x)!!!!!!!不过只要不是访问图像像素就问题不大
    // 2.计算子节点图像区域边界  1分为4  左上
    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);
    n1.vKeys.reserve(vKeys.size());	// reserve将容器的容量设置为至少vKeys.size
	
    // 右上 
    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.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.UL = n3.UR;
    n4.UR = n2.BR;
    n4.BL = n3.BR;
    n4.BR = BR;
    n4.vKeys.reserve(vKeys.size());

    // 把特征点分配到对应的4个节点区域
    for(size_t i=0;i<vKeys.size();i++)
    {	
        // 地址引用					
        const cv::KeyPoint &kp = vKeys[i];  // 注意vector数组容器中元素是cv::KeyPoint
        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);			// 右下
    }

    // 判断这几个子节点所属特征点数量 == 1,若为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;
}
b 实验测试
#include <iostream>
#include <vector>
#include <string>
#include <chrono>
#include <opencv2/opencv.hpp>
#include <opencv2/features2d.hpp>
#include "system.h"
#include "ORBextractor.h"
#include <cmath>

int main(int argc, char **argv)
{

    std::string datasetPath = "/home/wheeltec-client/WPJ/slam_data/000000.png";
    cv::Mat img1 = cv::imread(datasetPath);
    
    //  Fast角点测试
    std::vector<cv::KeyPoint> vKeysCell;
    cv::FAST(img1,vKeysCell,20,true);    // vKeysCell存储角点  initialThFast初始阈值
        
    cv::Mat outputImg;// 创建一个空白图像,用于绘制关键点
    cv::drawKeypoints(img1, vKeysCell, outputImg);
    // ExtractorNode 测试

       // 1.Compute how many initial nodes   一般是1或2
    const int nIni = round(static_cast<float>(img1.cols)/(img1.rows));  // 图像长/宽

    const float hX = static_cast<float>(img1.cols)/nIni;    // 每个节点的列范围

    std::list<ExtractorNode> lNodes; // 节点list列表,类型ExtractorNode,存放节点

    std::vector<ExtractorNode*> vpIniNodes;  // 节点指针
    vpIniNodes.resize(nIni);    // 最初容量至少=初始节点nIni

    // 2.生成初始提取器节点
    for(int i=0; i<nIni; i++)
    {
        ExtractorNode ni;
        // cv::Point2i 类的定义位于 <opencv2/core/types.hpp> 头文件中
        // 用于表示二维平面上的整数坐标点 i指int型  类模板Point_<T>
        ni.UL = cv::Point2i(hX*static_cast<float>(i),0); 
        ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);
        ni.BL = cv::Point2i(ni.UL.x,img1.rows);
        ni.BR = cv::Point2i(ni.UR.x,img1.rows);
        ni.vKeys.reserve(vKeysCell.size());

        // 把ni添加到 lNodes 容器的末尾
        lNodes.push_back(ni);
        // back() 是 list 容器的成员函数,用于获取容器中的最后一个元素
        // vpIniNodes节点指针 vpIniNodes[i]指针数组,指向当前节点
        // 存储这个初始的提取器节点句柄
        vpIniNodes[i] = &lNodes.back();
    }

    for(size_t i=0;i<vKeysCell.size();i++)
    {
        // 引用 kp
        const cv::KeyPoint &kp = vKeysCell[i];
        // kp.pt.x/hX初始化一般为1、2  存储到相应节点类成员对象vKeys
        vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
    }

    int i = 0;
    // 在绘制关键点后,绘制节点区域   
    for (const auto& node : lNodes) {

        // 遍历了节点列表 lNodes 中的每个节点,然后使用 cv::rectangle 函数在图像上绘制了一个矩形
        cv::rectangle(outputImg, node.UL, node.BR, cv::Scalar(0, 255, 0), 3); // 绘制矩形
        cv::Point2i center( (node.BR.x-node.UL.x) / 2+i*413,( node.BR.y-node.UL.y) / 2);    // 只计算区域中心!=实际坐标
        // cv::Point和cv::Point2i的构造函数接受的参数顺序是(x, y),即先是x坐标,然后是y坐标。
        // image.at<uchar>(y,x)注意图像时(v,u)!!!!!!!!!!
        cv::circle(outputImg, center, 10, cv::Scalar(0, 0, 255), -1); // 绘制圆点,蓝色
        i=i+1;
    }
    ExtractorNode n1,n2,n3,n4;
    lNodes.begin()->DivideNode(n1,n2,n3,n4);

    cv::rectangle(outputImg, n1.UL, n1.BR, cv::Scalar(0, 0, 255), 2); // 绘制矩形
    cv::rectangle(outputImg, n2.UL, n2.BR, cv::Scalar(0, 0, 255), 2); // 绘制矩形
    cv::rectangle(outputImg, n3.UL, n3.BR, cv::Scalar(0, 0, 255), 2); // 绘制矩形
    cv::rectangle(outputImg, n4.UL, n4.BR, cv::Scalar(0, 0, 255), 2); // 绘制矩形
    
    // 显示包含绘制了关键点和节点区域的图像窗口
    cv::imshow("Key Points and Nodes", outputImg);
    cv::waitKey(0);
    return 0;
}

在这里插入图片描述

在这里插入图片描述

6.3.2 多次分裂—特征点处理

​ 后续的节点分裂与上面相似,这里主要介绍一些其它情况

1 如果当前分裂后的节点区域内没有特征点,我们直接跳过该区域,删除这个节点,对应代码注释4.2。

2 如果当前分裂后的节点区域内只有1个特征点,我们不在分裂这个特征点,对应代码注释4.1。

3 如果下一次分裂的节点数 >=N,优先选择节点区域内特征点数目比较多的节点进行分裂,见注释5.6。

在这里插入图片描述

4 在不断的循环后,使得节点数 = N,选择每个节点区域内响应最大的节点作为该区域唯一特征点,注释7。

在这里插入图片描述

在这里插入图片描述

  • 程序分析: O R B e x t r a c t o r ORBextractor ORBextractor类内置函数
/**
 * @brief 使用四叉树法对一个图像金字塔图层中的特征点进行平均和分发
 * 
 * @param[in] vToDistributeKeys     等待进行分配到四叉树中的特征点
 * @param[in] minX                  当前图层的图像的边界,坐标都是在“半径扩充图像”坐标系下的坐标
 * @param[in] maxX 
 * @param[in] minY 
 * @param[in] maxY 
 * @param[in] N                     希望提取出的特征点个数
 * @param[in] level                 指定的金字塔图层,并未使用
 * @return vector<cv::KeyPoint>     已经均匀分散好的特征点vector容器
 */

// vector<cv::KeyPoint>是返回类型
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)
{
    // 1.Compute how many initial nodes   一般是1或2
    const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));  // 图像长/宽

    const float hX = static_cast<float>(maxX-minX)/nIni;    // 每个节点的列范围

    list<ExtractorNode> lNodes; // 节点list列表,类型ExtractorNode,存放节点

    vector<ExtractorNode*> vpIniNodes;  // 节点指针
    vpIniNodes.resize(nIni);    // 最初容量至少=初始节点nIni

    // 2.生成初始提取器节点
    for(int i=0; i<nIni; i++)
    {
        ExtractorNode ni;
        // cv::Point2i 类的定义位于 <opencv2/core/types.hpp> 头文件中
        // 用于表示二维平面上的整数坐标点 i指int型  类模板Point_<T>
        ni.UL = cv::Point2i(hX*static_cast<float>(i),0); 
        ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);
        ni.BL = cv::Point2i(ni.UL.x,maxY-minY);
        ni.BR = cv::Point2i(ni.UR.x,maxY-minY);
        ni.vKeys.reserve(vToDistributeKeys.size());

        // 把ni添加到 lNodes 容器的末尾
        lNodes.push_back(ni);
        // back() 是 list 容器的成员函数,用于获取容器中的最后一个元素
        // vpIniNodes节点指针 vpIniNodes[i]指针数组,指向当前节点
        // 存储这个初始的提取器节点句柄
        vpIniNodes[i] = &lNodes.back();
    }

    // 3. 把特征点分配给子节点(初始节点)
    for(size_t i=0;i<vToDistributeKeys.size();i++)
    {
        // 引用 kp
        const cv::KeyPoint &kp = vToDistributeKeys[i];
        // kp.pt.x/hX初始化一般为1、2  存储到相应节点类成员对象vKeys
        vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
    }

    // 4 遍历此提取器节点列表,标记那些不可再分裂的节点,删除那些没有分配到特征点的节点
    list<ExtractorNode>::iterator lit = lNodes.begin();

    while(lit!=lNodes.end())
    {
        if(lit->vKeys.size()==1)
        {
            lit->bNoMore=true; // 4.1 标志位,表示此节点不可再分
            lit++;
        }
        else if(lit->vKeys.empty())
            // 4.2 如果一个节点没有被分配到特征点,那么就从列表中直接删除它
            lit = lNodes.erase(lit);
        else
            lit++;
    }

    bool bFinish = false;

    int iteration = 0;

    // 这个变量记录了在一次分裂循环中,那些可以再继续进行分裂的节点中包含的特征点数目和其句柄(节点指针)
    vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;
    // 调整大小,一个初始化节点将“分裂”成为四个节点
    vSizeAndPointerToNode.reserve(lNodes.size()*4);


    // 5 利用四叉树方法对图像进行划分区域,均匀分配特征点
    while(!bFinish)
    {
        iteration++;

        // 节点数
        int prevSize = lNodes.size();

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

        vSizeAndPointerToNode.clear();

        while(lit!=lNodes.end())
        {
            if(lit->bNoMore)
            {
                // 5.1 当前节点只有一个特征点,不再分裂该特征点
                lit++;
                continue;
            }
            else
            {
                // 5.2 不止一个特征点, 1分为4
                ExtractorNode n1,n2,n3,n4;
                lit->DivideNode(n1,n2,n3,n4);

                // 5.3 如果分裂的子节点区域特征点数比0大,接下面操作;否则该区域将被抛弃
                if(n1.vKeys.size()>0)
                {
                    // 只要这个节点区域内特征点数>=1,添加n1子节点
                    lNodes.push_front(n1); // 把这个节点放在容器第一个位置
                    if(n1.vKeys.size()>1)
                    {
                        // 5.4 特征点数>1,说明还需要分裂(最终的目的就是每一个节点区域的特征点为1)
                        nToExpand++;
                        // 键值对数组容器  <n1节点特征点数,n1节点指针>
                        vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
                         // lNodes.front().lit 和前面的迭代的lit 不同,只是名字相同而已
                        // lNodes.front().lit是node结构体里的一个指针用来记录节点的位置
                        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();
                    }
                }

                lit=lNodes.erase(lit); // 删除分裂的母节点
                continue;
            }
        }       

        // 5.5 Finish 如果节点数>特征点数 or 所有的节点只有一个特征点
        if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
        {
            bFinish = true; // 结束循环
        }
        // 5.6 (int)lNodes.size()+nToExpand*3  实际分裂会得到节点数>N,那么选择特征点数比较大的节点分裂
        else if(((int)lNodes.size()+nToExpand*3)>N)
        {

            while(!bFinish)
            {
                // 获取当前的list中的节点个数
                prevSize = lNodes.size();

                vector<pair<int,ExtractorNode*> > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
                vSizeAndPointerToNode.clear();

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


                for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
                {
                    // 5.6.1 优先分裂特征点数比较大的节点
                    ExtractorNode n1,n2,n3,n4;
                    vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4);

                    // 5.6.2 Add childs if they contain points
                    if(n1.vKeys.size()>0)
                    {
                        lNodes.push_front(n1);
                        if(n1.vKeys.size()>1)
                        {
                            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,那么直接跳出for循环,不在分裂节点
                    if((int)lNodes.size()>=N)
                        break;
                }

                if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
                    bFinish = true;

            }
        }
    }

    // Retain the best point in each node
    // 7 到此,已经固定了最终的节点,但每个节点不一定只有一个特征点,我们保留每个节点区域响应值最大的一个特征点
    vector<cv::KeyPoint> vResultKeys;
    // 调整容器大小为要提取的特征点数目
    vResultKeys.reserve(nfeatures);
    for(list<ExtractorNode>::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
    {
        // 当前节点的特征点数组容器 引用
        vector<cv::KeyPoint> &vNodeKeys = lit->vKeys;
        // 7.1 得到指向第一个特征点的指针,后面作为最大响应值对应的关键点
        cv::KeyPoint* pKP = &vNodeKeys[0];
        // 7.2 用第1个关键点响应值初始化最大响应值
        float maxResponse = pKP->response;

        for(size_t k=1;k<vNodeKeys.size();k++)
        {
            if(vNodeKeys[k].response>maxResponse)
            {
                // 7.3 只要这个关键点的相应大,记录其地址指针
                pKP = &vNodeKeys[k];
                maxResponse = vNodeKeys[k].response;
            }
        }
        // 7.4 记录每一个节点中响应最大的关键点
        vResultKeys.push_back(*pKP);
    }
    // 8.返回最终关键点数组容器
    return vResultKeys;
}

6.3.3 对比opencv

#include <iostream>
#include <vector>
#include <string>
#include <chrono>
#include <opencv2/opencv.hpp>
#include <opencv2/features2d.hpp>
#include "system.h"
#include "ORBextractor.h"
#include <cmath>


int main(int argc, char **argv)
{
    ORBextractor test(1000,8,20,7,1.2);

    std::string datasetPath = "/home/wheeltec-client/WPJ/slam_data/000000.png";
    cv::Mat img1 = cv::imread(datasetPath,0);
    if (img1.empty()) {
        std::cerr << "Could not read image: " << std::endl;
        return 1;
    }
    
    assert(img1.type() == CV_8UC1 );   // 计算特征点主方向利用了image.a<uchar>
    

    test.ComputePyramid(img1);      // 将计算结果存储在类成员变量mvImagePyramid

    std::vector<std::vector<cv::KeyPoint>> all_of_perlevelkeypoints;
    test.ComputeKeyPointsOctTree(all_of_perlevelkeypoints);


    // 2. 利用opencv提取ORB特征点
    
    cv::Ptr<cv::Feature2D> detector = cv::ORB::create();
    std::vector<cv::KeyPoint> keypoints;
    detector->detect(img1, keypoints);


    // 在图像上绘制特征点
    cv::Mat outputImg1;// 创建一个空白图像,用于绘制关键点
    cv::drawKeypoints(img1, all_of_perlevelkeypoints[0], outputImg1);
    cv::Mat outputImg2;
    cv::drawKeypoints(img1, keypoints, outputImg2);

    cv::imshow("Key Points_my", outputImg1);
    cv::imshow("Key Points_cv", outputImg2);
    cv::waitKey(0);
    return 0;
}

在这里插入图片描述

7 ORBextractor类的使用

7.1 Frame

​ 特征点提取主要是在Frame构造函数中被调用,每有一帧图像输入,就要对其进行特征点提取。

成员变量/函数访问含义
ORBextractor* mpORBextractorLeftpublic左目特征提取指针
ORBextractor*mpORBextractorRightpublic右目特征提取指针
Frame()public构造函数中初始化左右目提取器指针,调用ExtractORB
ExtractORB(int flag, constcv::Mat &im)public调用(*mpORBextractorLeft)(im,cv::Mat(),mvKeys,mDescriptors)(*mpORBextractorRight)(im,cv::Mat(),mvKeysRight,mDescriptorsRight)

7.2 Tracking

mvpMapPoints = vector<MapPoint*>(N,static_cast<MapPoint*>(NULL));	// 初始化N个地图点(N个特征点)

Frame类中的特征提取指针mpORBextractor是在跟踪线程Tracking构造函数中创建。在Frame类调用完之后,只会保存当前帧Framenfeatures个特征点和地图点信息(初始化为NULL)。关于图像金字塔等局部变量就会被后续帧的变量代替,所以ORB-SLAM2是稀疏重建。

Tracking::Tracking(System *pSys, ORBVocabulary* pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer,
                   Map *pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor):
{

    // 加载ORB特征点有关的参数
	....

    // tracking过程都会用到mpORBextractorLeft作为特征点提取器
    mpORBextractorLeft = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);    // ORB提取类对象

    // 如果是双目,tracking过程中还会用用到mpORBextractorRight作为右目特征点提取器
    if(sensor==System::STEREO)
        mpORBextractorRight = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);

}


cv::Mat Tracking::GrabImageStereo(
    const cv::Mat &imRectLeft,      // 左侧图像
    const cv::Mat &imRectRight,     // 右侧图像
    const double &timestamp)        // 时间戳
{
    .....
        
    // Step 2 :构造Frame
    mCurrentFrame = Frame(
        mImGray,                //左目图像
        imGrayRight,            //右目图像
        timestamp,              //时间戳
        mpORBextractorLeft,     //左目特征提取器
        mpORBextractorRight,    //右目特征提取器
        mpORBVocabulary,        //字典
        mK,                     //内参矩阵
        mDistCoef,              //去畸变参数
        mbf,                    //基线长度
        mThDepth);              //远点,近点的区分阈值

}

8 关于ORB均匀化所带来的问题

  在数据集中,ORB-SLAM2算法表现是很不错的,但是往往在实际数据中,很容易跟踪失败(拐弯处尤其明显)ORB-SLAM2的均匀化特征提取的策略提高了系统的精度和鲁棒性。但在另一个角度,是不是也增加了跟踪失败了可能,即在一些场景下降低了ORB-SLAM2的跟踪鲁棒性?
​  ORB-SLAM2的均匀提取策略降低了特征的重复性,不利于保证同一个特征在多帧之间都提取到。提取ORB特征,一是为了构造地图点,二是为了实现数据关联。一个ORB特征点对应的地图点被越多的帧观测到,那么就能形成更好的map,从而也能保证系统的精度。也就是说,多帧之间的ORB特征应具有很好的重复性,这样才能保证形成强大的网络。一个地图点能够被越多的帧观测到越好。
​  总而言之,这种策略有优点也有一定的缺点。换句话说,对于不同的场景,要适配不同的策略。后续需要多做一些实验以验证问题。

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

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

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值