ORB-SLAM2 ---- ORBextractor::ComputePyramid

一、函数作用

	本函数是用来构建图像金字塔的,图像金字塔在 ORB-SLAM2 中的作用是通过多尺度处理来增强特征提取和匹配的鲁棒性,
确保系统能够在不同距离和缩放情况下正确地识别和跟踪特征点,从而提高 SLAM 系统的精度和效率。

二、源码及注释

void ORBextractor::ComputePyramid(cv::Mat image)
{
    // nlevels取值为8,即金字塔层数为8
    for (int level = 0; level < nlevels; ++level)
    {
        // 获取当前层级的缩放因子
        float scale = mvInvScaleFactor[level];
        // 根据缩放因子来计算当前层级的尺寸
        Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale)); // cvRound()作用是将括号内的内容四舍五入
        // 计算当前层图像的尺寸,加上边缘的安全区域,EDGE_THRESHOLD为边缘阈值
        Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
        // 创建大小为wholeSize的临时矩阵temp,类型与原图像相同
        Mat temp(wholeSize, image.type()), masktemp; // 创建的两个矩阵,第一个temp初始化了,用于存放扩展边界的图像,第二个masktamp未初始化,没用到

        // mvImagePyramid存储金字塔中每一层的图像,将temp的有效区域(去掉边缘部分)存储到当前层
        mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height)); //Rect前两个是左上角坐标,后面两个参数为长和高

        // Compute the resized image
        // 如果当前不是第0层,则根据上一层图像计算当前层图像
        if( level != 0 )
        {
            // 使用线性插值法将上一层图像resize到当前层的大小
            resize(mvImagePyramid[level-1],     // 输入的图像
                    mvImagePyramid[level],      // 输出的图像
                        sz,                     // 输出的图像尺寸 
                         0,                     // 水平方向上的缩放系数,0表示自动计算
                         0,                     // 垂直方向上的缩放系数,0表示自动计算
                          INTER_LINEAR);        // 插值算法的类型,这个代表线性插值法

            // 把源图像拷贝到目的图像的中央,四面填充指定的像素。图片如果已经拷贝到中间,只填充边界
			// 这样做是为了能够正确提取边界的FAST角点
			// EDGE_THRESHOLD指的这个边界的宽度,由于这个边界之外的像素不是原图像素而是算法生成出来的,所以不能够在EDGE_THRESHOLD之外提取特征点
            copyMakeBorder(mvImagePyramid[level],                                    // 源图像
                                            temp,                                    // 目标图像
                                             EDGE_THRESHOLD, EDGE_THRESHOLD,         // top & bottom 需要扩展的border大小
                                             EDGE_THRESHOLD, EDGE_THRESHOLD,         // left & right 需要扩展的border大小
                                            BORDER_REFLECT_101+BORDER_ISOLATED);     // 扩充方式       
        }
        else
        {
            //对于第0层未缩放图像,直接将图像深拷贝到temp的中间,并且对其周围进行边界扩展。此时temp就是对原图扩展后的图像
            copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
                           BORDER_REFLECT_101);            
        }
    }

}
} //namespace ORB_SLAM

三、函数传参

这个函数的传参只有一个cv::Mat image   cv::Mat类型的原图像 ,cv::Mat是OpenCV内置的一个类型,实际上代表的是一个矩阵

四、函数难点

	本函数代码部分我已经全部作了详细的注释,相信读者能很容易的看懂,其中resize(),copyMakeBorder(),copyMakeBorder()
三个函数为OpenCV的内置函数,读者不需要了解如何实现,应该了解其使用方法,特别是弄明白传递了那些参数,这些参数是什么含义。
	我认为本函数的难点在于,很多人不知道为什么要进行图像“补边”,原因是当算法检测图像边缘处的特征点时,由于邻域的一部分可能超出了图像边界,
导致该区域无法完整地执行特征提取,过扩展图像的边界,SLAM 系统可以避免边缘效应,并确保在构建图像金字塔时,不会因为边缘区域的信息不足而
影响特征检测和匹配的准确性。这是提高系统鲁棒性和精度的重要步骤。

在这里插入图片描述

五、学习代码的小积累之容器.xxx()的作用

我觉得这样的积累是有意义的,由于在学习代码时,没有将看到的全部记录下来,只记得小部分(以后碰到会添加进来):
 数组后面加.size()可以获得该数组的成员数量
 数组后面加.clear()清空该数组成员
 数组后面加.resize()改变数组成员个数
 数组后面加.push_back() 在数组后面追加一个成员(规定成员写在括号里面)
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值