ORBextractor.cc 代码详解

说明

由于本程序文件过长,所以将代码原理放置在了另外一个文件[ORBextractor.cc代码原理分析]

程序函数如下

#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <vector>

#include "ORBextractor.h"


using namespace cv;
using namespace std;

namespace ORB_SLAM2
{
    
    

const int PATCH_SIZE = 31;       //块的大小为31
const int HALF_PATCH_SIZE = 15;  //一半块的大小为15
const int EDGE_THRESHOLD = 19;   // 边界的阈值为19

// 根据ORB旋转不变性:该函数的功能是计算特征点与质心的夹角
// https://zhuanlan.zhihu.com/p/61738607
static float IC_Angle(const Mat& image, 
                      Point2f pt,                       //关键点坐标
                      const vector<int> & u_max)        // u_max代表,像素的横坐标
{
    
    
    int m_01 = 0, m_10 = 0;         // 根据公式初始化图像块的矩

    // cvRound函数:返回跟参数最接近的整数值,即四舍五入
    // pt默认为关键点
    const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));

    //第0行的像素值与纵坐标的乘积                                           问题:center[u]代表的是什么意思?灰度值?
    for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)  // u代表像素的横坐标
        m_10 += u * center[u];                                 // center[u]代表的是像素灰度值

    // Go line by line in the circular patch
    int step = (int)image.step1();      // 每行含有的元素个数
    for (int v = 1; v <= HALF_PATCH_SIZE; ++v)      // v代表像素的纵坐标
    {
    
    
        // Proceed over the two lines
        // 每次处理对称的两行
        int v_sum = 0;
        int d = u_max[v];   // 获得第v行所对应的纵坐标u
        for (int u = -d; u <= d; ++u)          
        {
    
       // 这里有点小bug,无法保证 u+v*step 在圆内
            int val_plus = center[u + v*step], val_minus = center[u - v*step]; // 获得对应点的像素灰度值
            v_sum += (val_plus - val_minus);        //因为val_minus对应的是-v,为了统一符号,用减法
            m_10 += u * (val_plus + val_minus);
        }
        m_01 += v * v_sum;  // 巧妙的避开了v=0的计算
    }
        //返回计算的角度
    return fastAtan2((float)m_01, (float)m_10);
}

//弧度制和角度制之间的转换
const float factorPI = (float)(CV_PI/180.f);
//计算ORB描述子
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);

    const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
    const int step = (int)img.step;

    #define GET_VALUE(idx) \
        center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
               cvRound(pattern[idx].x*a - pattern[id9x].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;
        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;
    }

    #undef GET_VALUE
}

// 解决描述子的区分性
//计算描述子的pattern,高斯分布,也可以使用其他定义的pattern
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)*/,
    7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/,
    2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/,
    1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/,
    -2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/,
    -13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/,
    -13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/,
    10,4, 11,9/*mean (0.122065), correlation (0.093285)*/,
    -13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/,
    -11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/,
    7,7, 12,6/*mean (0.160583), correlation (0.130064)*/,
    -4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/,
    -13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/,
    -9,0, -7,5/*mean (0.198234), correlation (0.143636)*/,
    12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/,
    -3,6, -2,12/*mean (0.166847), correlation (0.171682)*/,
    -6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/,
    11,-13, 12,-8/*mean (0.200641), correlation (0.192279)*/,
    4,7, 5,1/*mean (0.205106), correlation (0.186848)*/,
    5,-3, 10,-3/*mean (0.234908), correlation (0.192319)*/,
    3,-7, 6,12/*mean (0.0709964), correlation (0.210872)*/,
    -8,-7, -6,-2/*mean (0.0939834), correlation (0.212589)*/,
    -2,11, -1,-10/*mean (0.127778), correlation (0.20866)*/,
    -13,12, -8,10/*mean (0.14783), correlation (0.206356)*/,
    -7,3, -5,-3/*mean (0.182141), correlation (0.198942)*/,
    -4,2, -3,7/*mean (0.188237), correlation (0.21384)*/,
    -10,-12, -6,11/*mean (0.14865), correlation (0.23571)*/,
    5,-12, 6,-7/*mean (0.222312), correlation (0.23324)*/,
    5,-6, 7,-1/*mean (0.229082), correlation (0.23389)*/,
    1,0, 4,-5/*mean (0.241577), correlation (0.215286)*/,
    9,11, 11,-13/*mean (0.00338507), correlation (0.251373)*/,
    4,7, 4,12/*mean (0.131005), correlation (0.257622)*/,
    2,-1, 4,4/*mean (0.152755), correlation (0.255205)*/,
    -4,-12, -2,7/*mean (0.182771), correlation (0.244867)*/,
    -8,-5, -7,-10/*mean (0.186898), correlation (0.23901)*/,
    4,11, 9,12/*mean (0.226226), correlation (0.258255)*/,
    0,-8, 1,-13/*mean (0.0897886), correlation (0.274827)*/,
    -13,-2, -8,2/*mean (0.148774), correlation (0.28065)*/,
    -3,-2, -2,3/*mean (0.153048), correlation (0.283063)*/,
    -6,9, -4,-9/*mean (0.169523), correlation (0.278248)*/,
    8,12, 10,7/*mean (0.225337), correlation (0.282851)*/,
    0,9, 1,3/*mean (0.226687), correlation (0.278734)*/,
    7,-5, 11,-10/*mean (0.00693882), correlation (0.305161)*/,
    -13,-6, -11,0/*mean (0.0227283), correlation (0.300181)*/,
    10,7, 12,1/*mean (0.125517), correlation (0.31089)*/,
    -6,-3, -6,12/*mean (0.131748), correlation (0.312779)*/,
    10,-9, 12,-4/*mean (0.144827), correlation (0.292797)*/,
    -13,8, -8,-12/*mean (0.149202), correlation (0.308918)*/,
    -13,0, -8,-4/*mean (0.160909), correlation (0.310013)*/,
    3,3, 7,8/*mean (0.177755), correlation (0.309394)*/,
    5,7, 10,-7/*mean (0.212337), correlation (0.310315)*/,
    -1,7, 1,-12/*mean (0.214429), correlation (0.311933)*/,
    3,-10, 5,6/*mean (0.235807), correlation (0.313104)*/,
    2,-4, 3,-10/*mean (0.00494827), correlation (0.344948)*/,
    -13,0, -13,5/*mean (0.0549145), correlation (0.344675)*/,
    -13,-7, -12,12/*mean (0.103385), correlation (0.342715)*/,
    -13,3, -11,8/*mean (0.134222), correlation (0.322922)*/,
    -7,12, -4,7/*mean (0.153284), correlation (0.337061)*/,
    6,-10, 12,8/*mean (0.154881), correlation (0.329257)*/,
    -9,-1, -7,-6/*mean (0.200967), correlation (0.33312)*/,
    -2,-5, 0,12/*mean (0.201518), correlation (0.340635)*/,
    -12,5, -7,5/*mean (0.207805), correlation (0.335631)*/,
    3,-10, 8,-13/*mean (0.224438), correlation (0.34504)*/,
    -7,-7, -4,5/*mean (0.239361), correlation (0.338053)*/,
    -3,-2, -1,-7/*mean (0.240744), correlation (0.344322)*/,
    2,9, 5,-11/*mean (0.242949), correlation (0.34145)*/,
    -11,-13, -5,-13/*mean (0.244028), correlation (0.336861)*/,
    -1,6, 0,-1/*mean (0.247571), correlation (0.343684)*/,
    5,-3, 5,2/*mean (0.000697256), correlation (0.357265)*/,
    -4,-13, -4,12/*mean (0.00213675), correlation (0.373827)*/,
    -9,-6, -9,6/*mean (0.0126856), correlation (0.373938)*/,
    -12,-10, -8,-4/*mean (0.0152497), correlation (0.364237)*/,
    10,2, 12,-3/*mean (0.0299933), correlation (0.345292)*/,
    7,12, 12,12/*mean (0.0307242), correlation (0.366299)*/,
    -7,-13, -6,5/*mean (0.0534975), correlation (0.368357)*/,
    -4,9, -3,4/*mean (0.099865), correlation (0.372276)*/,
    7,-1, 12,2/*mean (0.117083), correlation (0.364529)*/,
    -7,6, -5,1/*mean (0.126125), correlation (0.369606)*/,
    -13,11, -12,5/*mean (0.130364), correlation (0.358502)*/,
    -3,7, -2,-6/*mean (0.131691), correlation (0.375531)*/,
    7,-8, 12,-7/*mean (0.160166), correlation (0.379508)*/,
    -13,-7, -11,-12/*mean (0.167848), correlation (0.353343)*/,
    1,-3, 12,12/*mean (0.183378), correlation (0.371916)*/,
    2,-6, 3,0/*mean (0.228711), correlation (0.371761)*/,
    -4,3, -2,-13/*mean (0.247211), correlation (0.364063)*/,
    -1,-13, 1,9/*mean (0.249325), correlation (0.378139)*/,
    7,1, 8,-6/*mean (0.000652272), correlation (0.411682)*/,
    1,-1, 3,12/*mean (0.00248538), correlation (0.392988)*/,
    9,1, 12,6/*mean (0.0206815), correlation (0.386106)*/,
    -1,-9, -1,3/*mean (0.0364485), correlation (0.410752)*/,
    -13,-13, -10,5/*mean (0.0376068), correlation (0.398374)*/,
    7,7, 10,12/*mean (0.0424202), correlation (0.405663)*/,
    12,-5, 12,9/*mean (0.0942645), correlation (0.410422)*/,
    6,3, 7,11/*mean (0.1074), correlation (0.413224)*/,
    5,-13, 6,10/*mean (0.109256), correlation (0.408646)*/,
    2,-12, 2,3/*mean (0.131691), correlation (0.416076)*/,
    3,8, 4,-6/*mean (0.165081), correlation (0.417569)*/,
    2,6, 12,-13/*mean (0.171874), correlation (0.408471)*/,
    9,-12, 10,3/*mean (0.175146), correlation (0.41296)*/,
    -8,4, -7,9/*mean (0.183682), correlation (0.402956)*/,
    -11,12, -4,-6/*mean (0.184672), correlation (0.416125)*/,
    1,12, 2,-8/*mean (0.191487), correlation (0.386696)*/,
    6,-9, 7,-4/*mean (0.192668), correlation (0.394771)*/,
    2,3, 3,-2/*mean (0.200157), correlation (0.408303)*/,
    6,3, 11,0/*mean (0.204588), correlation (0.411762)*/,
    3,-3, 8,-8/*mean (0.205904), correlation (0.416294)*/,
    7,8, 9,3/*mean (0.213237), correlation (0.409306)*/,
    -11,-5, -6,-4/*mean (0.243444), correlation (0.395069)*/,
    -10,11, -5,10/*mean (0.247672), correlation (0.413392)*/,
    -5,-8, -3,12/*mean (0.24774), correlation (0.411416)*/,
    -10,5, -9,0/*mean (0.00213675), correlation (0.454003)*/,
    8,-1, 12,-6/*mean (0.0293635), correlation (0.455368)*/,
    4,-6, 6,-11/*mean (0.0404971), correlation (0.457393)*/,
    -10,12, -8,7/*mean (0.0481107), correlation (0.448364)*/,
    4,-2, 6,7/*mean (0.050641), correlation (0.455019)*/,
    -2,0, -2,12/*mean (0.0525978), correlation (0.44338)*/,
    -5,-8, -5,2/*mean (0.0629667), correlation (0.457096)*/,
    7,-6, 10,12/*mean (0.0653846), correlation (0.445623)*/,
    -9,-13, -8,-8/*mean (0.0858749), correlation (0.449789)*/,
    -5,-13, -5,-2/*mean (0.122402), correlation (0.450201)*/,
    8,-8, 9,-13/*mean (0.125416), correlation (0.453224)*/,
    -9,-11, -9,0/*mean (0.130128), correlation (0.458724)*/,
    1,-8, 1,-2/*mean (0.132467), correlation (0.440133)*/,
    7,-4, 9,1/*mean (0.132692), correlation (0.454)*/,
    -2,1, -1,-4/*mean (0.135695), correlation (0.455739)*/,
    11,-6, 12,-11/*mean (0.142904), correlation (0.446114)*/,
    -12,-9, -6,4/*mean (0.146165), correlation (0.451473)*/,
    3,7, 7,12/*mean (0.147627), correlation (0.456643)*/,
    5,5, 10,8/*mean (0.152901), correlation (0.455036)*/,
    0,-4, 2,8/*mean (0.167083), correlation (0.459315)*/,
    -9,12, -5,-13/*mean (0.173234), correlation (0.454706)*/,
    0,7, 2,12/*mean (0.18312), correlation (0.433855)*/,
    -1,2, 1,7/*mean (0.185504), correlation (0.443838)*/,
    5,11, 7,-9/*mean (0.185706), correlation (0.451123)*/,
    3,5, 6,-8/*mean (0.188968), correlation (0.455808)*/,
    -13,-4, -8,9/*mean (0.191667), correlation (0.459128)*/,
    -5,9, -3,-3/*mean (0.193196), correlation (0.458364)*/,
    -4,-7, -3,-12/*mean (0.196536), correlation (0.455782)*/,
    6,5, 8,0/*mean (0.1972), correlation (0.450481)*/,
    -7,6, -6,12/*mean (0.199438), correlation (0.458156)*/,
    -13,6, -5,-2/*mean (0.211224), correlation (0.449548)*/,
    1,-10, 3,10/*mean (0.211718), correlation (0.440606)*/,
    4,1, 8,-4/*mean (0.213034), correlation (0.443177)*/,
    -2,-2, 2,-13/*mean (0.234334), correlation (0.455304)*/,
    2,-12, 12,12/*mean (0.235684), correlation (0.443436)*/,
    -2,-13, 0,-6/*mean (0.237674), correlation (0.452525)*/,
    4,1, 9,3/*mean (0.23962), correlation (0.444824)*/,
    -6,-10, -3,-5/*mean (0.248459), correlation (0.439621)*/,
    -3,-13, -1,1/*mean (0.249505), correlation (0.456666)*/,
    7,5, 12,-11/*mean (0.00119208), correlation (0.495466)*/,
    4,-2, 5,-7/*mean (0.00372245), correlation (0.484214)*/,
    -13,9, -9,-5/*mean (0.00741116), correlation (0.499854)*/,
    7,1, 8,6/*mean (0.0208952), correlation (0.499773)*/,
    7,-8, 7,6/*mean (0.0220085), correlation (0.501609)*/,
    -7,-4, -7,1/*mean (0.0233806), correlation (0.496568)*/,
    -8,11, -7,-8/*mean (0.0236505), correlation (0.489719)*/,
    -13,6, -12,-8/*mean (0.0268781), correlation (0.503487)*/,
    2,4, 3,9/*mean (0.0323324), correlation (0.501938)*/,
    10,-5, 12,3/*mean (0.0399235), correlation (0.494029)*/,
    -6,-5, -6,7/*mean (0.0420153), correlation (0.486579)*/,
    8,-3, 9,-8/*mean (0.0548021), correlation (0.484237)*/,
    2,-12, 2,8/*mean (0.0616622), correlation (0.496642)*/,
    -11,-2, -10,3/*mean (0.0627755), correlation (0.498563)*/,
    -12,-13, -7,-9/*mean (0.0829622), correlation (0.495491)*/,
    -11,0, -10,-5/*mean (0.0843342), correlation (0.487146)*/,
    5,-3, 11,8/*mean (0.0929937), correlation (0.502315)*/,
    -2,-13, -1,12/*mean (0.113327), correlation (0.48941)*/,
    -1,-8, 0,9/*mean (0.132119), correlation (0.467268)*/,
    -13,-11, -12,-5/*mean (0.136269), correlation (0.498771)*/,
    -10,-2, -10,11/*mean (0.142173), correlation (0.498714)*/,
    -3,9, -2,-13/*mean (0.144141), correlation (0.491973)*/,
    2,-3, 3,2/*mean (0.14892), correlation (0.500782)*/,
    -9,-13, -4,0/*mean (0.150371), correlation (0.498211)*/,
    -4,6, -3,-10/*mean (0.152159), correlation (0.495547)*/,
    -4,12, -2,-7/*mean (0.156152), correlation (0.496925)*/,
    -6,-11, -4,9/*mean (0.15749), correlation (0.499222)*/,
    6,-3, 6,11/*mean (0.159211), correlation (0.503821)*/,
    -13,11, -5,5/*mean (0.162427), correlation (0.501907)*/,
    11,11, 12,6/*mean (0.16652), correlation (0.497632)*/,
    7,-5, 12,-2/*mean (0.169141), correlation (0.484474)*/,
    -1,12, 0,7/*mean (0.169456), correlation (0.495339)*/,
    -4,-8, -3,-2/*mean (0.171457), correlation (0.487251)*/,
    -7,1, -6,7/*mean (0.175), correlation (0.500024)*/,
    -13,-12, -8,-13/*mean (0.175866), correlation (0.497523)*/,
    -7,-2, -6,-8/*mean (0.178273), correlation (0.501854)*/,
    -8,5, -6,-9/*mean (0.181107), correlation (0.494888)*/,
    -5,-1, -4,5/*mean (0.190227), correlation (0.482557)*/,
    -13,7, -8,10/*mean (0.196739), correlation (0.496503)*/,
    1,5, 5,-13/*mean (0.19973), correlation (0.499759)*/,
    1,0, 10,-13/*mean (0.204465), correlation (0.49873)*/,
    9,12, 10,-1/*mean (0.209334), correlation (0.49063)*/,
    5,-8, 10,-9/*mean (0.211134), correlation (0.503011)*/,
    -1,11, 1,-13/*mean (0.212), correlation (0.499414)*/,
    -9,-3, -6,2/*mean (0.212168), correlation (0.480739)*/,
    -1,-10, 1,12/*mean (0.212731), correlation (0.502523)*/,
    -13,1, -8,-10/*mean (0.21327), correlation (0.489786)*/,
    8,-11, 10,-6/*mean (0.214159), correlation (0.488246)*/,
    2,-13, 3,-6/*mean (0.216993), correlation (0.50287)*/,
    7,-13, 12,-9/*mean (0.223639), correlation (0.470502)*/,
    -10,-10, -5,-7/*mean (0.224089), correlation (0.500852)*/,
    -10,-8, -8,-13/*mean (0.228666), correlation (0.502629)*/,
    4,-6, 8,5/*mean (0.22906), correlation (0.498305)*/,
    3,12, 8,-13/*mean (0.233378), correlation (0.503825)*/,
    -4,2, -3,-3/*mean (0.234323), correlation (0.476692)*/,
    5,-13, 10,-12/*mean (0.236392), correlation (0.475462)*/,
    4,-13, 5,-1/*mean (0.236842), correlation (0.504132)*/,
    -9,9, -4,3/*mean (0.236977), correlation (0.497739)*/,
    0,3, 3,-9/*mean (0.24314), correlation (0.499398)*/,
    -12,1, -6,1/*mean (0.243297), correlation (0.489447)*/,
    3,2, 4,-8/*mean (0.00155196), correlation (0.553496)*/,
    -10,-10, -10,9/*mean (0.00239541), correlation (0.54297)*/,
    8,-13, 12,12/*mean (0.0034413), correlation (0.544361)*/,
    -8,-12, -6,-5/*mean (0.003565), correlation (0.551225)*/,
    2,2, 3,7/*mean (0.00835583), correlation (0.55285)*/,
    10,6, 11,-8/*mean (0.00885065), correlation (0.540913)*/,
    6,8, 8,-12/*mean (0.0101552), correlation (0.551085)*/,
    -7,10, -6,5/*mean (0.0102227), correlation (0.533635)*/,
    -3,-9, -3,9/*mean (0.0110211), correlation (0.543121)*/,
    -1,-13, -1,5/*mean (0.0113473), correlation (0.550173)*/,
    -3,-7, -3,4/*mean (0.0140913), correlation (0.554774)*/,
    -8,-2, -8,3/*mean (0.017049), correlation (0.55461)*/,
    4,2, 12,12/*mean (0.01778), correlation (0.546921)*/,
    2,-5, 3,11/*mean (0.0224022), correlation (0.549667)*/,
    6,-9, 11,-13/*mean (0.029161), correlation (0.546295)*/,
    3,-1, 7,12/*mean (0.0303081), correlation (0.548599)*/,
    11,-1, 12,4/*mean (0.0355151), correlation (0.523943)*/,
    -3,0, -3,6/*mean (0.0417904), correlation (0.543395)*/,
    4,-11, 4,12/*mean (0.0487292), correlation (0.542818)*/,
    2,-4, 2,1/*mean (0.0575124), correlation (0.554888)*/,
    -10,-6, -8,1/*mean (0.0594242), correlation (0.544026)*/,
    -13,7, -11,1/*mean (0.0597391), correlation (0.550524)*/,
    -13,12, -11,-13/*mean (0.0608974), correlation (0.55383)*/,
    6,0, 11,-13/*mean (0.065126), correlation (0.552006)*/,
    0,-1, 1,4/*mean (0.074224), correlation (0.546372)*/,
    -13,3, -9,-2/*mean (0.0808592), correlation (0.554875)*/,
    -9,8, -6,-3/*mean (0.0883378), correlation (0.551178)*/,
    -13,-6, -8,-2/*mean (0.0901035), correlation (0.548446)*/,
    5,-9, 8,10/*mean (0.0949843), correlation (0.554694)*/,
    2,7, 3,-9/*mean (0.0994152), correlation (0.550979)*/,
    -1,-6, -1,-1/*mean (0.10045), correlation (0.552714)*/,
    9,5, 11,-2/*mean (0.100686), correlation (0.552594)*/,
    11,-3, 12,-8/*mean (0.101091), correlation (0.532394)*/,
    3,0, 3,5/*mean (0.101147), correlation (0.525576)*/,
    -1,4, 0,10/*mean (0.105263), correlation (0.531498)*/,
    3,-6, 4,5/*mean (0.110785), correlation (0.540491)*/,
    -13,0, -10,5/*mean (0.112798), correlation (0.536582)*/,
    5,8, 12,11/*mean (0.114181), correlation (0.555793)*/,
    8,9, 9,-6/*mean (0.117431), correlation (0.553763)*/,
    7,-4, 8,-12/*mean (0.118522), correlation (0.553452)*/,
    -10,4, -10,9/*mean (0.12094), correlation (0.554785)*/,
    7,3, 12,4/*mean (0.122582), correlation (0.555825)*/,
    9,-7, 10,-2/*mean (0.124978), correlation (0.549846)*/,
    7,0, 12,-2/*mean (0.127002), correlation (0.537452)*/,
    -1,-6, 0,-11/*mean (0.127148), correlation (0.547401)*/
};
//ORB提取器
ORBextractor::ORBextractor(int _nfeatures,      // 指定要提取的特征点数目
                           float _scaleFactor,  // 指定图像金字塔的缩放系数
                           int _nlevels,        // 指定图像金字塔的层数
                           int _iniThFAST,      // 指定初始的FAST特征点提取参数,可以提取出最明显的角点
                           int _minThFAST):     //  如果因为图像纹理不丰富提取出的特征点不多,为了达到想要的
                                                // 的特征点数目,就是用这个参数提取出不是那么明显的角点
    nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
    iniThFAST(_iniThFAST), minThFAST(_minThFAST)
{
    
    
    //存储每层图像缩放系数的vector,调整为符合图层数目的大小
    mvScaleFactor.resize(nlevels);
    // 存储这个sigma^2,其实就是每层图像相对初始图像缩放因子的平方
    mvLevelSigma2.resize(nlevels);
    // 对于初始图像,这两个参数都是1
    mvScaleFactor[0]=1.0f;
    mvLevelSigma2[0]=1.0f;
    // 然后逐层计算图像金字塔中图像相当于初始图像的缩放系数
    for(int i=1; i<nlevels; i++)
    {
    
       // 其实就是这样累乘计算得出来的
        mvScaleFactor[i]=mvScaleFactor[i-1]*scaleFactor;
        // 原来这里的sigma^2就是每层图像相对于初始图像缩放因子的平方
        mvLevelSigma2[i]=mvScaleFactor[i]*mvScaleFactor[i];
    }
    // 接下来的两个向量保存上面的参数的倒数,操作都是一样大的就不在赘述了
    mvInvScaleFactor.resize(nlevels);
    mvInvLevelSigma2.resize(nlevels);
    //计算逆尺度大小
    for(int i=0; i<nlevels; i++)
    {
    
    
        mvInvScaleFactor[i]=1.0f/mvScaleFactor[i];
        mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
    }

    // 调整图像金字塔vector以使得其符合咱们设定的图像层数
    mvImagePyramid.resize(nlevels);
    // 每层需要提取出来的特征点个数,这个向量也要根据图像金字塔设定的层数进行调整
    mnFeaturesPerLevel.resize(nlevels);
    // 图片降采样缩放系数的倒数
    float factor = 1.0f / scaleFactor;
    //第0层应包含的特征点数
    // 该公式来源 , 根据资料https://zhuanlan.zhihu.com/p/61738607
    float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));

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

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

    //This is for orientation
    // pre-compute the end of a row in a circular patch
     // 定义一个vector,用来保存每个v对应的最大坐标u
    umax.resize(HALF_PATCH_SIZE + 1);

    // 将v坐标划分为两部分计算,为了确保计算特征主方向的时候,x,y方向对称
    int v,  // 循环辅助变量
        v0, // 辅助变量
        //cvFloor():返回不大于参数的最大整数值,即向下取整;
        vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.f) / 2 + 1);
       // 计算圆的最大行号, +1应该是把中间行也给考虑进去了
       // 注意 这里的最大行号指的是计算的时候的最大行号,此行和圆的交点在45°圆心角的一边上,
       // 之所以这样选择是因为圆周上的对称特性
    
    // 这里的二分之根2就是对应那个45°圆心角
    int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.f) / 2);  //cvCeil():返回不小于参数的最小整数值,即向上取整;
    // 半径的平方
    const double hp2 = HALF_PATCH_SIZE*HALF_PATCH_SIZE;
    // 利用圆的方程计算每行像素的u坐标边界(max)
    for (v = 0; v <= vmax; ++v)
        umax[v] = cvRound(sqrt(hp2 - v * v));//勾股定理

    // 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;
    }
}
//计算每个关键点的角度
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);//根据之前函数计算得到角度
    }
}
// 将提取器节点分成4个节点,同时也完成图像区域的划分、特征点归属的划分,以及相关标志位的置位
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.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());

    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());

    //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;

}
//计算FAST选出来的特征点是否合格
// 使用八叉树法(实际上是四叉树)对一个图层中的特征点进行平均和分发
vector<cv::KeyPoint> ORBextractor::DistributeOctTree(// 返回值是一个保存有特征点的vector容器
    const vector<cv::KeyPoint>& vToDistributeKeys,  // 等待进行分配到八叉树中的特征点,注意根据后面ComputerKeyPointsOctTree函数中的定义
                                   // NOTICE 这里特征点中使用的坐标都是在“半径扩充图像”坐标系下的坐标
    const int& minX,        // 当前图层的图像的边界,根据后面ComputerKeyPointsOctTree函数中的定义,这里使用的
    const int& maxX,        // NOTICE 其实就是相对于当前图层“边缘扩充图像”下的坐标
    const int& minY,
    const int& maxY,
    const int& N,           // 希望提取出的特征点个数
    const int& level)       //NOTICE 指定的图层,但是在本函数中其实并没有用到这个参数
    // 注意到这个函数应该是直接使用成员函数,图像金字塔中的图像,因为并没有出现任何图像的函数参数
{
    
    
    // Compute how many initial nodes   
    //将影像进行水平划分
     // nIni 是水平划分的数量
    // 计算应该生成的初始节点个数,根节点的主梁nIni是根据边界的宽高比值确定的,一般是1或者2
    const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));// 这里有一个bug,如果图像是一个像手机一样的图片,该变量有可能取0,下面的程序就无冲说起了!!!
    //hX是水平划分格子的宽度(一个初始的节点的x方向有多少个像素)
    const float hX = static_cast<float>(maxX-minX)/nIni;
    // 存储有提取基节点的列表
    list<ExtractorNode> lNodes;
    // 存储初始提取器节点指针的vector
    vector<ExtractorNode*> vpIniNodes;
    // 然后重新设置其大小
    vpIniNodes.resize(nIni);
    // 生成指定个数的初始提取基接点
    for(int i=0; i<nIni; i++)
    {
    
       // 生成一个提取节点
        ExtractorNode ni;
        // 设置提取基接点的图像边界
        // NOTICE 注意根据这个逻辑, 当i=0的时候,ni.UL=0, 这个看样子就不是“半径扩充图像”下的坐标了!! TODO
        // 下面这里的节点的边界先都按照“边缘扩充图像”下的坐标系来理解
        ni.UL = cv::Point2i(hX*static_cast<float>(i),0);    // UpLeft
        ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);  // UpRight
        // NOTICE 注意这里是直接到了图像的底部,也就是说,按照作者的意思,应该是图像的width>hight?
        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());
        // 将刚才生成的提取节点添加到列表中
        // NOTICE 虽然这里的ni是局部变量,但是由于这里的std:vector::push_back()是拷贝参数的内容到一个新的对象中然后再添加到列表中
        // 的, 所以当本函数退出之后这里的内存不会成为“野指针”
        lNodes.push_back(ni);
        // 存储这个初始的提取器节点句柄
        vpIniNodes[i] = &lNodes.back();
    }

    //Associate points to childs
    // 将特征点分配到子提取器节点中
    // 开始遍历等待分配的提取器节点
    for(size_t i=0;i<vToDistributeKeys.size();i++)
    {
    
    
        // 获取这个特征点对象
        const cv::KeyPoint &kp = vToDistributeKeys[i];
        // 按特征点的横轴位置,分配给属于那个图像区域的提取器节点(最初的提取器节点)
        // NOTICE TODO 这里特征点的坐标是相对于“半径扩充图像”坐标系下的啊!
        vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
    }// 将特征点分配到子提取器节点中,开始遍历等待分配的提取器节点
    // 当遍历次提取器节点列表,标记那些不可再分裂的节点,删除那些没有分配到特征点的节点
    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;
    // NOTICE 迭代次数,用于累计第一组分裂时的迭代次数,但是在后文中并没有得到实际的使用
    int iteration = 0;
    // 声明一个vector用于存储节点的vSize和句柄对
    // 这个变量记录了在一次分裂循环中,那些在继续进行分裂的节点中包含的特征点数目和其句柄
    vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;
    // 调整大小,这里的意思是一个初始化节点将“分裂”成为四个,当然实际上不会有那么多,这里多分配了一些只是预防万一
    vSizeAndPointerToNode.reserve(lNodes.size()*4);
    // 对于每个node而言,若其只有一个特征点,bNoMore为true,表明其不用再继续划分
    // 根据兴趣点分布,利用N叉树方法对图像进行划分区域
    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)
            {
    
    
                // If node only contains one point do not subdivide and continue
               //那么就没有必要再进行细分了
                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
                // 如果这里分出来的子区域中有特征点,那么就将这个子区域的节点添加到提取器节点的列表中
                // NOTICE 注意这里的条件是,有特征点即可
                if(n1.vKeys.size()>0)
                {
    
       //将这四个节点中含有的特征点的节点存入lNodes的最前面
                    // 注意这里也是添加到列表前面的
                    lNodes.push_front(n1); 
                    // 如果分裂出的节点中特征点的个数大于1,说明还可以分裂,将特征点数,节点的指针存入vSizeAndPointerToNode中,
                  //nToExpand计数器加1,后面用于判断可分裂的能力
                    // 在判断其中子提取器节点中的特征点数目是否大于1
                    if(n1.vKeys.size()>1)
                    {
    
    
                        // 如果有超过一个的特征点,那么“待展开的节点计数++”
                        nToExpand++;
                        // 保存这个特征点数目和节点指针的信息
                        vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
                        // TODO 貌似是通过这里给子节点提供了一个访问这里列表lNodes的方式?可是后面通过这里的lNodes.begin()发生更新了怎么办?
                        // 这个时候就不在
                        //NOTICE 此外目前来看,这个访问用的句柄在本文件中也是没有用到
                        // lNodes.front().lit和前面的迭代的lit不同,只是名字相同而已
                        // lNodes.front().lit是node结构体李的一个指针用来记录节点的位置
                        // 迭代的lit 是while循环里作者命名的遍历的指针名称
                        lNodes.front().lit = lNodes.begin();
                        //分裂成四个节点ont().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的
                // 分裂方式是先加的先分裂,后加的后分裂,因为下面最后一个母节点erase后,指针指向的是lNodes.end(),推出while循环,进入后面的判断了,下
                lit=lNodes.erase(lit);
                // 继续下一次循环,其实这里加不加这句话的作用都是一样的
                // 继续当前遍历到的节点中是否有超过一个特征点
                continue;
            }//判断当前遍历到节点中是否有超过一个的特征点
        }//遍历列表中的所有提取器节点

        // Finish if there are more nodes than required features
        // or all nodes contain just one point
            //分裂之后进行判断
        //如果当前节点数量大于等于需要的特征点数(N),或者分裂过程并没有增加节点的数量,说明不需要进行分裂了,跳出循环
        // 停止这个过程的条件有两个
        // 1、当前的节点数已经超过了要求的特征点数
        // 2、当前所有的节点中都只包含一个特征点
        // 满足其中一个即可
        if((int)lNodes.size()>=N            // 判断是否超过了要求的特征点数
            || (int)lNodes.size()==prevSize)    // prevSize中保存的是分裂之前的节点个数,如果分裂之前和分裂之后的总结点个数一样,说明当前所有的
                                                // 节点区域中只有一个特征点,已经不能够再细分了
        {
    
       // 停止标志置位
            bFinish = true;
        }
        //继续判断条件,如果所有节点在进行一次分类,就可以满足特征点数量的要求了
        // 当再划分之后所有的Node数大于要求数目时
        // 就慢慢划分直到使其刚刚达到或者超过要求的特征点个数
        // 这里原本应该是nToExpend x4, nToExpand表示的可以展开的子节点个数
        // 即一个list中的sub-node分裂为4个subsub-Node,数目上看是增加了三个(因为在所有点的subsub-node添加到list之后,sub-node会被删除)
        // so 这里是nToExpand x3
        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对的第一个元素进行排序,默认是从小到大排序
                // NOTICE 这样一开始分裂的节点都是在特征点没有呢么密集的区域,也就是说,让特征点系数的区别尽可能保留更多的特征点(排在前面的更
                //  有机会参加),而特征点密集的区域保留风少的特征点(排在后面的节点获得分裂的机会更少)
                sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
                // 遍历这个存储了pair对的vector,注意不是遍历整个list了
                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数目刚刚达到或者超过要求的特征点数目
        }// 当本次分裂后达不到结束条件但是再进行一次完整的分裂之后就可以达到结束条件时
    }// 根据兴趣点分布,利用n叉树方法对图像进行划分区域,这里的N应该是=4

    // Retain the best point in each node
       //取出每个节点中响应最大的特征点
    // 保留每个区域响应值最大的一个兴趣点
    // 使用这个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];
        // 初始化最大响应值
        float maxResponse = pKP->response;
        // 开始遍历这个节点区域中的特征点容器中的特征点,注意是从1开始
        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;
}// TODO 只有我觉得这里应该是四叉树

//对影像金字塔中的每一层图像进行特征点的计算。具体计算过程是将影像网格分割成小区域,每一
//个小区域独立使用FAST角点检测
//检测完成之后使用DistributeOcTree函数对检测到所有的角点进行筛选,使得角点分布均匀
void ORBextractor::ComputeKeyPointsOctTree(
    vector<vector<KeyPoint> >& allKeypoints) // 所有特征点,这里第一层vector存储的是某图层里面的所有特征点
                                            // 第二层存储的是整个图像金字塔中的所有图层里面的所有特征点   
{
    
    
    //一共计算nlevel个尺度的关键点(重新调整图像层数)
    allKeypoints.resize(nlevels);
    //窗口的大小
    // 图像cell的尺寸,十个正方形,可以理解为边长in像素坐标
    const float W = 30;
    // 对每一层图像做处理
    // 遍历所有图像
    // 对每个尺度计算它的关键点
    for (int level = 0; level < nlevels; ++level)

    {
    
    
        //计算边界,在这个边界内计算FAST关键点
        // 计算着层图像的坐标边界,NOTICE 注意这里是坐标边界,EDGE_THRESHOLD指的应该是可以提取特征点
        // 的有效图像边界,后面会一直使用“有效图像边界”这个自变量
        const int minBorderX = EDGE_THRESHOLD-3;// 这里的是因为在计算FAST特征点的时候,需要建立一个半径为3的圆
        const int minBorderY = minBorderX;  // minY 的计算就可以直接拷贝上面的计算结果了
        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;
            // 计算当前网络最大的行坐标,这里的+6 = +3+3, 即考虑到了多出来以便进行FAST特征点提取用的3像素边界
            //前面的EDGE_THRESHOLD指的应该是提取后的特征点所在的边界,所以minBorderY是在考虑了计算半径是后的图像边界
            // 目前一个图像网络的大小是25*25啊
            float maxY = iniY+hCell+6;
            // 如果初始的行坐标就已经超过了有效的图像边界了,这里的“有效图像”是指原始的,可以提取FAST特征点的图像区域
            if(iniY>=maxBorderY-3) // 那么就跳过这一行
                continue;
            // 如果图像的大小大致不能够正好划分出来整齐的图像网格,那么就要委屈最后一行了
            if(maxY>maxBorderY)
                maxY = maxBorderY;
            // 开始列的遍历
            for(int j=0; j<nCols; j++)
            {
    
    
                //计算=初始的列坐标
                const float iniX =minBorderX+j*wCell;
                // 计算这列网络的最大列坐标,+6的含义和前面相同
                float maxX = iniX+wCell+6;
                // 判断坐标是否在图像中
                // TODO 不太能够明白为什么要-6, 前面不都是-3吗
                // ?BUG 疑似bug,源程序的确就是这样子写的
                if(iniX>=maxBorderX-6)
                    continue;
                // 如果最大坐标越界那么委屈一下
                if(maxX>maxBorderX)
                    maxX = maxBorderX;
                // FAST提取兴趣点,自适应阈值
                // 这个向量存储这个cell中的特征点
                vector<cv::KeyPoint> vKeysCell;
                // 调用OpenCV的库函数来检测FAST角点
                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
                // 当图像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];
        //至少保留n个特征点
        // 并且调整其大小为欲提取出来的特征点个数(当然这里也是扩大了的,
        // 因为不可能所有的特征点都是在这一个图层中提取出来的)
        keypoints.reserve(nfeatures);
        //根据Harris角点的score进行排序,保留正确的
        // 根据mnFeaturesPerLevel, 即该层的兴趣点数,对特征点进行删除
        // 返回值是一个保存有特征点的vector容器,含有删除后的保留下来的的特征点
        // 得到的特征点的坐标,依旧是在当前图层下来讲的
        keypoints = DistributeOctTree(vToDistributeKeys,  // 当前图层提取出来的特征点,也即是等待剔除的特征点
                                                          // NOTICE 注意此时特征点所使用的坐标都是在“半径扩充图像”下的
                                      minBorderX, maxBorderX,   //当前图层图像的边界,而这里的坐标却都是在“边缘扩充图像”下的
                                      minBorderY, maxBorderY,
                                      mnFeaturesPerLevel[level],// 希望保留下来的当前图像的特征点个数
                                      level);                   // 当前层图像所在的图层

        //PATCH_SIZE是31
        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);
}

void ORBextractor::ComputeKeyPointsOld(std::vector<std::vector<KeyPoint> > &allKeypoints)
{
    
    
    allKeypoints.resize(nlevels);

    float imageRatio = (float)mvImagePyramid[0].cols/mvImagePyramid[0].rows;

    for (int level = 0; level < nlevels; ++level)
    {
    
    
        const int nDesiredFeatures = mnFeaturesPerLevel[level];

        const int levelCols = sqrt((float)nDesiredFeatures/(5*imageRatio));
        const int levelRows = imageRatio*levelCols;

        const int minBorderX = EDGE_THRESHOLD;
        const int minBorderY = minBorderX;
        const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD;
        const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD;

        const int W = maxBorderX - minBorderX;
        const int H = maxBorderY - minBorderY;
        const int cellW = ceil((float)W/levelCols);
        const int cellH = ceil((float)H/levelRows);

        const int nCells = levelRows*levelCols;
        const int nfeaturesCell = ceil((float)nDesiredFeatures/nCells);

        vector<vector<vector<KeyPoint> > > cellKeyPoints(levelRows, vector<vector<KeyPoint> >(levelCols));

        vector<vector<int> > nToRetain(levelRows,vector<int>(levelCols,0));
        vector<vector<int> > nTotal(levelRows,vector<int>(levelCols,0));
        vector<vector<bool> > bNoMore(levelRows,vector<bool>(levelCols,false));
        vector<int> iniXCol(levelCols);
        vector<int> iniYRow(levelRows);
        int nNoMore = 0;
        int nToDistribute = 0;


        float hY = cellH + 6;

        for(int i=0; i<levelRows; i++)
        {
    
    
            const float iniY = minBorderY + i*cellH - 3;
            iniYRow[i] = iniY;

            if(i == levelRows-1)
            {
    
    
                hY = maxBorderY+3-iniY;
                if(hY<=0)
                    continue;
            }

            float hX = cellW + 6;

            for(int j=0; j<levelCols; j++)
            {
    
    
                float iniX;

                if(i==0)
                {
    
    
                    iniX = minBorderX + j*cellW - 3;
                    iniXCol[j] = iniX;
                }
                else
                {
    
    
                    iniX = iniXCol[j];
                }


                if(j == levelCols-1)
                {
    
    
                    hX = maxBorderX+3-iniX;
                    if(hX<=0)
                        continue;
                }


                Mat cellImage = mvImagePyramid[level].rowRange(iniY,iniY+hY).colRange(iniX,iniX+hX);

                cellKeyPoints[i][j].reserve(nfeaturesCell*5);

                FAST(cellImage,cellKeyPoints[i][j],iniThFAST,true);

                if(cellKeyPoints[i][j].size()<=3)
                {
    
    
                    cellKeyPoints[i][j].clear();

                    FAST(cellImage,cellKeyPoints[i][j],minThFAST,true);
                }


                const int nKeys = cellKeyPoints[i][j].size();
                nTotal[i][j] = nKeys;

                if(nKeys>nfeaturesCell)
                {
    
    
                    nToRetain[i][j] = nfeaturesCell;
                    bNoMore[i][j] = false;
                }
                else
                {
    
    
                    nToRetain[i][j] = nKeys;
                    nToDistribute += nfeaturesCell-nKeys;
                    bNoMore[i][j] = true;
                    nNoMore++;
                }

            }
        }


        // Retain by score

        while(nToDistribute>0 && nNoMore<nCells)
        {
    
    
            int nNewFeaturesCell = nfeaturesCell + ceil((float)nToDistribute/(nCells-nNoMore));
            nToDistribute = 0;

            for(int i=0; i<levelRows; i++)
            {
    
    
                for(int j=0; j<levelCols; j++)
                {
    
    
                    if(!bNoMore[i][j])
                    {
    
    
                        if(nTotal[i][j]>nNewFeaturesCell)
                        {
    
    
                            nToRetain[i][j] = nNewFeaturesCell;
                            bNoMore[i][j] = false;
                        }
                        else
                        {
    
    
                            nToRetain[i][j] = nTotal[i][j];
                            nToDistribute += nNewFeaturesCell-nTotal[i][j];
                            bNoMore[i][j] = true;
                            nNoMore++;
                        }
                    }
                }
            }
        }

        vector<KeyPoint> & keypoints = allKeypoints[level];
        keypoints.reserve(nDesiredFeatures*2);

        const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];

        // Retain by score and transform coordinates
        for(int i=0; i<levelRows; i++)
        {
    
    
            for(int j=0; j<levelCols; j++)
            {
    
    
                vector<KeyPoint> &keysCell = cellKeyPoints[i][j];
                KeyPointsFilter::retainBest(keysCell,nToRetain[i][j]);
                if((int)keysCell.size()>nToRetain[i][j])
                    keysCell.resize(nToRetain[i][j]);


                for(size_t k=0, kend=keysCell.size(); k<kend; k++)
                {
    
    
                    keysCell[k].pt.x+=iniXCol[j];
                    keysCell[k].pt.y+=iniYRow[i];
                    keysCell[k].octave=level;
                    keysCell[k].size = scaledPatchSize;
                    keypoints.push_back(keysCell[k]);
                }
            }
        }

        if((int)keypoints.size()>nDesiredFeatures)
        {
    
    
            KeyPointsFilter::retainBest(keypoints,nDesiredFeatures);
            keypoints.resize(nDesiredFeatures);
        }
    }

    // and compute orientations
    for (int level = 0; level < nlevels; ++level)
        computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
}
//计算描述子
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));
}
//输入的变量
// _image:获取的灰度图像
// _mask:掩码
// _keypoints:关键点位置
// _descriptors:描述子
//括号运算符输入图像,并且传入引用参数_keypoints,_descriptors用于计算得到的特征点及其描述子
// 这种设计使得只需要构造一次ORBextractor就可以为为所有图像生成特征点
void ORBextractor::operator()( InputArray _image,    // 输入图像
                               InputArray _mask,     // 用于辅助进行图像处理的掩膜
                               vector<KeyPoint>& _keypoints,// 特征点vector容器
                               OutputArray _descriptors)   // 以及用于输出的描述子mat
{
    
     
    //=======================准备阶段================
    // 如果没有获取图片,返回
    if(_image.empty())
        return;
    // 获取图像的大小
    Mat image = _image.getMat();
    //判断图像的格式是否正确
    assert(image.type() == CV_8UC1 );

    // Pre-compute the scale pyramid
     //构建图像金字塔
    ComputePyramid(image);
    // --------------------特征点提取和分配--------------------
    // 计算这里涉及的神奇之处,上面所有函数形参中的allKeypoints本质上都是来源于这里的allKeypoints,
    // 关键是这个变量在这里还是一个局部变量,实际上在最后处理的时候,是将这个变量中存储的所有特征点
    // 复制到返回用的vector中,达到传递当前图像中特征点的目的
    // 保存所有的关键点
    vector < vector<KeyPoint> > allKeypoints;
    // 计算关键点,找到FAST关键点
    // 使用八叉树的方式计算每层图像特征点并进行分配
    ComputeKeyPointsOctTree(allKeypoints);
    // 这里是使用传统的方法提取并平均分配图像的特征点
    //ComputeKeyPointsOld(allKeypoints);

    // =================描述子计算=====================
    // 保存描述子用的变量
    Mat descriptors;

    // 统计整个图像金字塔中的特征点
    int nkeypoints = 0;
    for (int level = 0; level < nlevels; ++level)
        nkeypoints += (int)allKeypoints[level].size();
    if( nkeypoints == 0 )
        _descriptors.release();
    else
    {
    
    
        _descriptors.create(nkeypoints, 32, CV_8U);
        descriptors = _descriptors.getMat();
    }

    _keypoints.clear();
    _keypoints.reserve(nkeypoints);

    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();
        //使用高斯模糊为了计算BRIEF的时候去噪
        GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);

        // Compute the descriptors
        //计算描述子,采用的是高斯分布取点,就是上面一长串的patten
        Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
        computeDescriptors(workingMat, keypoints, desc, pattern);

        offset += nkeypointsLevel;

        // Scale keypoint coordinates
         // 对关键点的位置坐做尺度恢复,恢复到原图的位置
        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;
        }
        // And add the keypoints to the output
        _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
    }
}
//建立金字塔
// 输入图像,这个输入图像所有像素都是有效的,也就是说都是可以在其上提取出FAST角点
void ORBextractor::ComputePyramid(cv::Mat image)
{
    
    
    // 开始遍历所有的图层
    // 计算n个level尺度的图片
    for (int level = 0; level < nlevels; ++level)
    {
    
    
        //获取本层图像的缩放系数
        float scale = mvInvScaleFactor[level];
        //获取当前尺度下图片的尺寸,根据金字塔模型,层数越高,尺度越大,scale是取的逆尺度因子
       // 所以层数越高,图片尺寸越小(计算本层图像的像素尺寸大小)
        Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
        // 真正的包括无效图像区域的大小,实际上作者这样做是将图像进行“裁边”,EDGE_THRESHOLS区域内的图像不进行FAST角点检测
        Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
        // 声明两个临时变量,第一个保持和有效图像大小相同,另外一个看上去是要作为掩膜
        // NOTE 后者其实在程序中并没有被使用到
        Mat temp(wholeSize, image.type()), masktemp;
        // 把图像金字塔该图层的图像copy给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表示自动计算
                INTER_LINEAR);          // 图像缩放的差值算法类型,这里的是线性插值算法
            // 在图像周围以对称的方式加一个宽度为EDGE_THRESHOLD的边,便于后面的计算
            // 把原图像拷贝到目的图像的中央,四面填充指定的像素,图像如果已经拷贝到中间,只填充边界
            // TODO 貌似这样做事因为在计算描述子前,进行高斯滤波的时候,图像边界会导致一些问题,所不明白
            // 而前面定义的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给出的解释
           // 为什么要进行扩充边界? 因为描述子要进行高斯滤波,边界无法滤波,所以进行边界扩充
        }
        else
        {
    
    
            // 对于底层图像,直接就扩充边界了
            // temp 输出并没有拷贝给mvImagePyramid
            //第一张为原图分辨率,无需缩放
            copyMakeBorder(image,   // 这里是货真价实的原图像
                temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                           BORDER_REFLECT_101);            
        }
    }

}

} //namespace ORB_SLAM

猜你喜欢

转载自blog.csdn.net/jlm7689235/article/details/107879674