ORB-SLAM2中生成金字塔提取FAST角点和计算BRIEF描述子

//这个是类ORBextractor的带参构造函数,并且使用初始化列表对该类中的这5个变量赋值
ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels,
         int _iniThFAST, int _minThFAST):
    nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
    iniThFAST(_iniThFAST), minThFAST(_minThFAST)
{
    //mvScaleFactor是用来存储金字塔中每层图像对应的尺度因子的vector变量
    //所以他的大小就是金字塔的层数
    mvScaleFactor.resize(nlevels);
    //mvLevelSigma2是该层尺度因子的平方,有点表示面积的意思,具体含义等遇到了再解释
    mvLevelSigma2.resize(nlevels);
    //将vector中的第一个元素值初始化为1.
    mvScaleFactor[0]=1.0f;
    mvLevelSigma2[0]=1.0f;
    //计算金字塔中每一层图像对应的尺度因子和尺度因子的平方。
    //可以发现金字塔中第0层的尺度因子是1,然后每向上高一层,图像的尺度因子是在上一层图像的尺度因子 
    //上乘以scaleFactor,在本工程下该值为1.2
    //1   1*1.2   1*1.2*1.2    1*1.2*1.2*1.2   ...
    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];
        mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
    }
    //mvImagePyramid是一个存储金字塔图像的vector,vector中的每一个元素是用Mat数据类型表示的图        
    //像, std::vector<cv::Mat> mvImagePyramid;
    mvImagePyramid.resize(nlevels);
    
    //mnFeaturesPerLevel是一个存储金字塔中每层图像应该提取的特征点的个数
    //std::vector<int> mnFeaturesPerLevel;

    mnFeaturesPerLevel.resize(nlevels);
    //那在这里factor = 1/1.2;
    float factor = 1.0f / scaleFactor;
    
    //nDesiredFeaturesPerScale是根据总的要在整幅图像中提取的特征点数nFeatures(在这里是1000)
    //还有金字塔的层数来计算每层图像上应该提取的特征点的个数。
    //根据下面的程序可以得知nDesiredFeaturesPerScale是第0层图像上应该提取的特征点的个数
    float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));

    int sumFeatures = 0;
    for( int level = 0; level < nlevels-1; level++ )
    {
        //那么mnFeaturesPerLevel[0]就是上面计算出来的这个值喽
        mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
        //由于四舍五入的原因将实际计算出的数值加到一起与预设的1000比较
        sumFeatures += mnFeaturesPerLevel[level];
        //层数越高则需要提取的特征的个数就越少,并且相邻层图像上提取的特征点的个数存在1.2倍
        //关系
        //这里是我计算的结果
        //217+180+150+125+104+87+72+60 = 995
        nDesiredFeaturesPerScale *= factor;
    }
    //看到这里就会知道上面为啥要把计算出来的特征点个数求和的原因了,就是来决定最后
    //一层图像应该提取的特征的个数了,根据计算最后一层要提取60个点,那现在就得提取65个
    //才能达到总共提取1000个点的要求。
    mnFeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);

    //下面这一块是为了提取特征点做准备了,等后面再讲解。
    const int npoints = 512;
    const Point* pattern0 = (const Point*)bit_pattern_31_;
    std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));

    //This is for orientation
    // pre-compute the end of a row in a circular patch
    umax.resize(HALF_PATCH_SIZE + 1);

    int v, v0, vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.f) / 2 + 1);
    int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.f) / 2);
    const double hp2 = HALF_PATCH_SIZE*HALF_PATCH_SIZE;
    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;
    }
}

//下面这个函数实现对输入的图像计算图像金字塔的任务
void ORBextractor::ComputePyramid(cv::Mat image)
{
    //nlevels = 8
    for (int level = 0; level < nlevels; ++level)
    {
        //在构造函数中已经提前定义好了每一层图像对应的反向尺度因子
        float scale = mvInvScaleFactor[level];
        
        //不同的level,scale的值不同所以就算出了每一层上的图像的大小
        Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
        //为新生成的图像加上边界
        Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
        //根据上面的计算的尺度来创建一幅新的图像, Mat类型
        //type()是Mat类中的一个成员函数,返回数据类型
        Mat temp(wholeSize, image.type()), masktemp;
        //mvImagePyramid是用来存储每一层图像的vector变量,为他的每一个元素设置特定大小的图像
        //mvImagePyramid[0]中存储的是原图像
        //通过Rect定义temp图像的左上侧起点和右下侧终点
        mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));

        // Compute the resized image
        if( level != 0 )
        {
            //mvImagePyramid[1]开始,都是由上一层的图像的尺寸得到
            // dsize = Size(round(fx*src.cols), round(fy*src.rows))
            //dsize是输出图像的大小,按照上面的计算公式计算得到了已经
            //resize(InputArry src, Output dst, Size dsize, double fx = 0, double fy = 0, 
            //int interpolation = INTER_LINEAR)
            resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, INTER_LINEAR);
            //将设置出的图像分别拷贝到相应的层上去
            copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                           BORDER_REFLECT_101+BORDER_ISOLATED);            
        }
        else
        {
            copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                           BORDER_REFLECT_101);            
        }
    }

}


//函数的三要素是:函数名称,函数参数, 函数返回值
//ComputeKeyPointsOctTree是类ORBextractor的成员函数
//参数是vector类型的引用变量allKeypoints.
//返回值是void类型
//在参数文件TUM1.yaml下预定义了一些变量的值
//ORBextractor. nFeatures: 1000
//ORBextractor. scaleFactor: 1.2
//ORBextractor. nlevels: 8
//ORBextractor. iniThFAST: 20
//ORBextractor. minThFAST: 7
//在ORBextractor.h中用带参构造函数来初始化类ORBextractor中的相应的变量
//在类ORBextractor中还有一串变量
//std::vector<float> mvScaleFactor;
//std::vector<float> mvInvScaleFactor;
//std::vector<float> mvlevelSifma2;
//std::vector<float> mvInvLevelSigma2;
//如果说第一组变量是金字塔中某一层图像的属性,那么第二组是成员变量是一幅图像的属性。
void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint> >& allKeypoints)
{
    //通过vector中的resize函数来重新将vector变量allKeypoints的大小设置为nlevels.
    //nlevels也就是图像金字塔中图像的层数
    allKeypoints.resize(nlevels);
   
    const float W = 30;
    //对金字塔中的每一层图像进行一系列的操作
    for (int level = 0; level < nlevels; ++level)
    {
        //EDGE_THRESHOLD=19
        //minBorderX, minBorderY, maxBorderX, maxBorderY四个变量一起设定了用于提取特征的区域
        const int minBorderX = EDGE_THRESHOLD-3;
        const int minBorderY = minBorderX;
        const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
        const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
        
        //定义变量vToDistributeKeys存储从每一层图像中提取出来的特征。
        //vector中存储的数据类型是在opencv中定义的KeyPoint类
        vector<cv::KeyPoint> vToDistributeKeys;

        //reserve:分配空间,更改capacity但是不改变size 预留空间
        //resize:分配空间,同时改变capacity和size
        vToDistributeKeys.reserve(nfeatures*10);

        //丈量了可以用来进行操作的“场地”大小
        const float width = (maxBorderX-minBorderX);
        const float height = (maxBorderY-minBorderY);

        //预将图像划分为30*30的网状
        //计算每个小格子的长和宽各占多少个像素
        const int nCols = width/W;
        const int nRows = height/W;

        ///计算最终长和宽被分成了多少个小格子cell
        const int wCell = ceil(width/nCols);
        const int hCell = ceil(height/nRows);
        
        //通过控制i来纵向遍历每一个cell
        for(int i=0; i<nRows; i++)
        {
           
            const float iniY =minBorderY+i*hCell;
            //这里maxY相当于给当前遍历的这个cell加上一个外框
            float maxY = iniY+hCell+6;

            if(iniY>=maxBorderY-3)
                continue;
            if(maxY>maxBorderY)
                maxY = maxBorderY;
            //通过控制j来横向遍历每一个cell.
            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;
                 //通过上面的两个for循环就可以完成遍历该层图像中所有的cell.
                
                //vKeysCell用来盛放该cell中提取的特征点
                vector<cv::KeyPoint> vKeysCell;
                //变量i和j的组合控制,当遍历到(i, j)个cell时,就提取这个cell下的FAST角点
                //如下是opencv中FAST函数的原型
                //输入图像,输出提取的特征点, 选取特征点的阈值
                ///FAST( InputArray image, CV_OUT vector<KeyPoint>& keypoints,
                /// int threshold, bool nonmaxSuppression=true );
                FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                     vKeysCell,iniThFAST,true);

                if(vKeysCell.empty())
                {
                    ///如果按照上面的方法在这个cell中提取不到特征点,那么就放低要求,
                    //用minThFAST阈值来提取FAST角点
                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                         vKeysCell,minThFAST,true);
                }

                if(!vKeysCell.empty())
                {
              //如果已经提取到关键点,那么就遍历这些所有提取的关键点
                    for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
                    {
///迭代器vit就相当于一个指向vector中存储的KeyPoint的指针,通过*vit就可以获取指针所指向的的
//特定的点
                        //pt表示KeyPoint的位置属性
                  //KeyPoint是opencv中的一个类,pt是该类中的一个属性,获取获取关键点的坐标
//因为单纯的(*vit).pt.x和(*vit).pt.y表示在当前cell下的坐标,还要转化为在可提取特征范围内的坐标
                        (*vit).pt.x+=j*wCell;
                        (*vit).pt.y+=i*hCell;
               //把从每个cell中提取的特征点都存储到vector变量vToDistributeKeys中去
                        vToDistributeKeys.push_back(*vit);
                    }
                }

            }
        }
//截止到这里已经将该层图像中的所有cell遍历结束并且,将提取的所有的特征点都已经存储到vector
//变量vToDistributeKeys中去了
       
        //vector<vector<KeyPoint> >& allKeypoints
        //allKeypoints是一个用来存储vector的vector
        //allKeypoints的大小是金字塔的层数nlevels
        //allKeypoints[level]是一个对应于每层图像上提取的特征点的vector
        //allKeypoints[level].size也就是在该层上要提取的特征点的个数
        vector<KeyPoint> & keypoints = allKeypoints[level];

        //keypoints的预留内存是每幅图像上所有要提取的特征数。
        keypoints.reserve(nfeatures);
        ////所有提取的关键点,提取的范围,是从哪一层上提取的特征
        ///下面这部分是将提取的关键点进行八叉树优化
        keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
                                      minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);
        ///PATCH_SIZE指代什么呢
        ////level=0表示原图像,随着层数的增加图像越来越小,那么在每幅图像上提取的特征个数
//也会相应的减少
        // PATCH_SIZE = 31.
        //vector变量mvScaleFactor中存储了一幅图像对应的一个金字塔中所有层图像的尺度因子
        //不同层图像的尺度因子不同,那么在该层中提取的特征点所对应的有效区域就不同。
        const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];

        //nkps表示keypoints中的特征点的个数
        const int nkps = keypoints.size();
        
        for(int i=0; i<nkps ; i++)
        {
     ///遍历在该层图像上提取的所有的特征点,在这些特征点坐标上都加上整幅图像的边界信息就可以
//得到关键点在整幅图像中的坐标
            keypoints[i].pt.x+=minBorderX;
            keypoints[i].pt.y+=minBorderY;

            //类KeyPoint一个成员变量octave用来存储该特征点是在哪一层图像上提取得到的。
            //我们之后在使用某一个特征点的时候就可以直接通过特的这个属性来知道他是从
//哪一层图像上提取出来的。

            keypoints[i].octave=level;

            ///这每一个关键点的size该如何理解呢,大概是根据近大远小的原理来计算的。
            ////在不同层图像上提取的点所表征的面积范围不同。

            keypoints[i].size = scaledPatchSize;
        }
    }

    // 遍历每一层图像以及在该层上提取的特征点,计算每个特征点的方向。
    for (int level = 0; level < nlevels; ++level)
        computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
}

总结:

如何更以更清晰的思路来分析和学习ORB-SLAM呢,我认为一种好的方式就是编译器如何利用C++这种工具来创建和维护该工程下一些变量的。如用来检测闭环和重定位,local BA,full BA,用来描述系统中关键帧之间的共视关系的covisibility graph, 以及由covisibility graph得到的 Enssential graph进行位姿图优化。 以上主要是利用C++下的强大的STL中的容器的概念来创建和存储这些关系如 std::map<KeyFrame* int> mConnectedKeyFrameWeights; 用map来存储了与当前帧有共视关系的关键帧以及共视的地图点的个数。

要知道帧与帧的联系是通过地图点建立起来的,并且在创建特征点的时候为这个地图点添加observation属性,用map来存储这个地图点可以被那个关键帧观测到,以及对应于该图像中的特征点的index.

而对于新进来的一幅图像我们要对她进行预处理,创建金字塔,提取FAST角点和计算BRIEF描述子,

用变量std::vector<cv::Mat> mvImagePyramid 来存储计算出来的金字塔中的每一层图像

用变量std::vector<std::vector>allKeypoints来存储金字塔中每一层图像中提取的特征点。

用变量std::vector<float> mvScaleFactor来存储金字塔中每一层图像对应的尺度因子

用变量std::vector<int> mnFeaturesPerLevel来存储金字塔中每一幅图像应该提取的特征点的个数

最后这两个变量都是在类ORBextractor中的构造函数中计算初始化的。

输入一幅图像首先要计算8层金字塔,然后是针对于金字塔中的每一层图像划分为grid来提取特征点, 然后将这些特征点用八叉树进行优化,然后在计算描述子,和观测方向。

猜你喜欢

转载自blog.csdn.net/weixin_38636815/article/details/81943109