ORB-SLAM2 ---- ORBextractor::ComputeKeyPointsOctTree

一、函数作用

ORB-SLAM2 ---- ORBextractor::DistributeOctTree是此函数的基础,此函数是除主函数外最重要的一个函数,此函数的主要作用是对特征点进行处理(提取,分配,计算方向信息)

二、源码及注释

void ORBextractor::ComputeKeyPointsOctTree(
    vector<vector<KeyPoint> >& allKeypoints)// 所有的特征点,这里第一层vector存储的是某图层里面的所有特征点,
												// 第二层存储的是整个图像金字塔中的所有图层里面的所有特征点
{
    // 该容器是存放不同层数的所有特征点,一共nlevels = 8层,初始化一下
    allKeypoints.resize(nlevels);

    // 一个网格单元的边长,网格单元为正方形
    const float W = 30;

    // 遍历每一层图像
    for (int level = 0; level < nlevels; ++level)
    {
        // EDGE_THRESHOLD为扩充的边界,加减3是因为特征点分析时,要留出半径为3的圆,使得周围有16个像素可以进行灰度比较
        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;

        // k开辟一个需要分配的特征点容器
        vector<cv::KeyPoint> vToDistributeKeys;
        // 因为要过量提取后在删除部分,所以开辟的空间应该大一些
        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++)
        {
            // 计算每个小单元的左上y坐标和左下y坐标
            const float iniY =minBorderY+i*hCell;
            float maxY = iniY+hCell+6;

            // 直到上边界超出取特征点区域,进入下一次循环
            if(iniY>=maxBorderY-3)
                continue;
            // 下边界如果大于取特征点区域,则将其设置为下边界
            // 如果图像的大小导致不能够正好划分出来整齐的图像网格,那么就要委屈最后一行了
            if(maxY>maxBorderY)
                maxY = maxBorderY;
            
            // 行列采取相同的操作不赘述
            for(int j=0; j<nCols; j++)
            {
                const float iniX =minBorderX+j*wCell;
                float maxX = iniX+wCell+6;
                if(iniX>=maxBorderX-6)
                    continue;
                if(maxX>maxBorderX)
                    maxX = maxBorderX;

                // 这个容器存储提取到的特征点
                vector<cv::KeyPoint> vKeysCell; // 为什么每次循环不用清空这个容器
                // 调用FAST来提取该单元格角点
                FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),// 待检测的图像,这里就是当前遍历到的图像块
                    vKeysCell,      // 存储角点位置的容器
                    iniThFAST,      // 检测阈值  ORBextractor.iniThFAST: 20
                    true);          // 使能非极大值抑制


                // 如果这个图像块中使用默认的FAST检测阈值没有能够检测到角点
                if(vKeysCell.empty())
                {
                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                         vKeysCell,minThFAST,true); // ORBextractor.minThFAST: 7
                }
                
                // 如果有角点进行下面的操作
                if(!vKeysCell.empty())
                {
                    // 遍历其中的所有的FAST角点
                    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);
        // 调用DistributeOctTree,返回已经被分配好特征点的容器
        keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
                                      minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);

        // 当前图层的缩放因子
        const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
        // 获取剔除过程后保留下来的特征点数目
        const int nkps = keypoints.size();

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

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

三、函数的讲解

因为此函数代码量较大,我们分几段来讲解

1. 遍历金字塔的每一层,将其分成30*30的网格单元,并给每一层添加图像边界

这段代码已经详细标注了,相信读者能看懂,难点在于为什么要这样做

  1. 第一点就是为什么要添加图像边界,为什么要加减3,在识别角点的时候用的是灰度对比法,特征点需要与旁边半径为3的圆的特定16个点比较灰度,这个加减3就是为了防止边缘的角点对比灰度时缺失像素点,添加图像边界EDGE_THRESHOLD,这个边界扩展方式是 BORDER_REFLECT_101(ORBextractor::ComputePyramid中有提到),即通过镜像反射图像边缘的像素来填充扩展区域。这种扩展方式不会引入额外的噪声或突兀的边界像素,确保了图像的平滑性,增强了特征提取的鲁棒性。
  2. 第二点就是很多初学者好奇最后四行代码是干吗,这不是重复计算了吗,其实这里是有一个四舍五入的,在算一次是为了保证完整覆盖图像
allKeypoints.resize(nlevels);

    // 一个网格单元的边长,网格单元为正方形
    const float W = 30;

    // 遍历每一层图像
    for (int level = 0; level < nlevels; ++level)
    {
        // EDGE_THRESHOLD为扩充的边界,加减3是因为特征点分析时,要留出半径为3的圆,使得周围有16个像素可以进行灰度比较
        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;

        // k开辟一个需要分配的特征点容器
        vector<cv::KeyPoint> vToDistributeKeys;
        // 因为要过量提取后在删除部分,所以开辟的空间应该大一些
        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);

2. 遍历每个单元格,提取特征点

这段代码前面的部分,在补充分配单元格的内容,简单来说就是分到最后一行不足30了,就委屈一下最后一行列少分配一些,后续调用
FAST ()角点提取器来提取角点(角点优先作为特征点),如果该网格内没有角点,就降低阈值进行提取特征值,特征值提取好后,遍历这些提取出来的特征值,将特征点的坐标转换到【坐标边界】下的坐标。其中FAST ()函数是OpenCV中内置的函数。

// 遍历每个小单元格
        for(int i=0; i<nRows; i++)
        {
            // 计算每个小单元的左上y坐标和左下y坐标
            const float iniY =minBorderY+i*hCell;
            float maxY = iniY+hCell+6;

            // 直到上边界超出取特征点区域,进入下一次循环
            if(iniY>=maxBorderY-3)
                continue;
            // 下边界如果大于取特征点区域,则将其设置为下边界
            // 如果图像的大小导致不能够正好划分出来整齐的图像网格,那么就要委屈最后一行了
            if(maxY>maxBorderY)
                maxY = maxBorderY;
            
            // 行列采取相同的操作不赘述
            for(int j=0; j<nCols; j++)
            {
                const float iniX =minBorderX+j*wCell;
                float maxX = iniX+wCell+6;
                if(iniX>=maxBorderX-6)
                    continue;
                if(maxX>maxBorderX)
                    maxX = maxBorderX;

                // 这个容器存储提取到的特征点
                vector<cv::KeyPoint> vKeysCell; // 为什么每次循环不用清空这个容器
                // 调用FAST来提取该单元格角点
                FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),// 待检测的图像,这里就是当前遍历到的图像块
                    vKeysCell,      // 存储角点位置的容器
                    iniThFAST,      // 检测阈值  ORBextractor.iniThFAST: 20
                    true);          // 使能非极大值抑制


                // 如果这个图像块中使用默认的FAST检测阈值没有能够检测到角点
                if(vKeysCell.empty())
                {
                    FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
                         vKeysCell,minThFAST,true); // ORBextractor.minThFAST: 7
                }
                
                // 如果有角点进行下面的操作
                if(!vKeysCell.empty())
                {
                    // 遍历其中的所有的FAST角点
                    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);
                    }
                }

            }
        }

3. 调用DistributeOctTree()函数分配特征点

这段代码先调用DistributeOctTree()来分配提取出来的特征点,然后遍历这些特征点,将其坐标转换到当前图层图像坐标系下

// 声明一个对当前图层的特征点的容器的引用
vector<KeyPoint> & keypoints = allKeypoints[level];
        // 开辟他的大小为想要提取的特征点数量
        keypoints.reserve(nfeatures);
        // 调用DistributeOctTree,返回已经被分配好特征点的容器
        keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
                                      minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);

        // 当前图层的缩放因子
        const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
        // 获取剔除过程后保留下来的特征点数目
        const int nkps = keypoints.size();

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

4. 计算所有保留下来的特征点的方向信息

computeOrientation()函数在ORB-SLAM ---- IC_Angle()这篇中讲过

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值