ORB-SLAM2第二节---双目地图初始化

news2024/11/25 13:50:40

比起单目初始化,而双目实现地图的初始化非常简单,只需要一帧(左右目图像)即可完成初始化。

  1. 行特征点统计。考虑用图像金字塔尺度作为偏移量,在当前点上下正负偏移量(r)内的纵坐标值都认为是匹配点可能存在的行数。之所以这样做,是因为极线矫正后仍然存在一定的误差,通过这种方式可以避免漏匹配。对于左图中极线上的投影像素点,在右图中搜索的纵坐标范围是minr~maxr。
  2. 粗匹配。在左图中的特征点与右图中的候选匹配点进行逐个比较,得到描述子距离最小的点作为最佳的粗匹配点。根据三维点的距离范围可以将横坐标搜索范围限制在minU~maxU。maxU对应的是三维点位于无穷远处,视差为0时的横坐标,而minU对应的是三维点位于最近距离时的横坐标。
  3. 在粗匹配的基础上,在图像块滑动窗口内用差的绝对和(Sum of Absolute Differences,SAD)实现精确匹配。此时得到的匹配像素坐标仍然是整数坐标。如图10-4,

 

 

/*
 * 双目匹配函数
 *
 * 为左图的每一个特征点在右图中找到匹配点 \n
 * 根据基线(有冗余范围)上描述子距离找到匹配, 再进行SAD精确定位 \n ‘
 * 这里所说的SAD是一种双目立体视觉匹配算法,可参考[https://blog.csdn.net/u012507022/article/details/51446891]
 * 最后对所有SAD的值进行排序, 剔除SAD值较大的匹配对,然后利用抛物线拟合得到亚像素精度的匹配 \n 
 * 这里所谓的亚像素精度,就是使用这个拟合得到一个小于一个单位像素的修正量,这样可以取得更好的估计结果,计算出来的点的深度也就越准确
 * 匹配成功后会更新 mvuRight(ur) 和 mvDepth(Z)
 */
void Frame::ComputeStereoMatches()
{
    /*两帧图像稀疏立体匹配(即:ORB特征点匹配,非逐像素的密集匹配,但依然满足行对齐)
     * 输入:两帧立体矫正后的图像img_left 和 img_right 对应的orb特征点集
     * 过程:
          1. 行特征点统计. 统计img_right每一行上的ORB特征点集,便于使用立体匹配思路(行搜索/极线搜索)进行同名点搜索, 避免逐像素的判断.
          2. 粗匹配. 根据步骤1的结果,对img_left第i行的orb特征点pi,在img_right的第i行上的orb特征点集中搜索相似orb特征点, 得到qi
          3. 精确匹配. 以点qi为中心,半径为r的范围内,进行块匹配(归一化SAD),进一步优化匹配结果
          4. 亚像素精度优化. 步骤3得到的视差为uchar/int类型精度,并不一定是真实视差,通过亚像素差值(抛物线插值)获取float精度的真实视差
          5. 最优视差值/深度选择. 通过胜者为王算法(WTA)获取最佳匹配点。
          6. 删除离群点(outliers). 块匹配相似度阈值判断,归一化sad最小,并不代表就一定是正确匹配,比如光照变化、弱纹理等会造成误匹配
     * 输出:稀疏特征点视差图/深度图(亚像素精度)mvDepth 匹配结果 mvuRight
     */

    // 为匹配结果预先分配内存,数据类型为float型
    // mvuRight存储右图匹配点索引
    // mvDepth存储特征点的深度信息
	mvuRight = vector<float>(N,-1.0f);
    mvDepth = vector<float>(N,-1.0f);

	// orb特征相似度阈值  -> mean ~= (max  + min) / 2
    const int thOrbDist = (ORBmatcher::TH_HIGH+ORBmatcher::TH_LOW)/2;

    // 金字塔底层(0层)图像高 nRows
    const int nRows = mpORBextractorLeft->mvImagePyramid[0].rows;

	// 二维vector存储每一行的orb特征点的列坐标的索引,为什么是vector,因为每一行的特征点有可能不一样,例如
    // vRowIndices[0] = [1,2,5,8, 11]   第1行有5个特征点,他们的列号(即x坐标)分别是1,2,5,8,11
    // vRowIndices[1] = [2,6,7,9, 13, 17, 20]  第2行有7个特征点.etc
    vector<vector<size_t> > vRowIndices(nRows, vector<size_t>());
    for(int i=0; i<nRows; i++) vRowIndices[i].reserve(200);

	// 右图特征点数量,N表示数量 r表示右图,且不能被修改
    const int Nr = mvKeysRight.size();

	// Step 1. 行特征点统计。 考虑用图像金字塔尺度作为偏移,左图中对应右图的一个特征点可能存在于多行,而非唯一的一行
    for(int iR = 0; iR < Nr; iR++) {

        // 获取特征点ir的y坐标,即行号
        const cv::KeyPoint &kp = mvKeysRight[iR];
        const float &kpY = kp.pt.y;
        
        // 计算特征点ir在行方向上,可能的偏移范围r,即可能的行号为[kpY + r, kpY -r]
        // 2 表示在全尺寸(scale = 1)的情况下,假设有2个像素的偏移,随着尺度变化,r也跟着变化
        const float r = 2.0f * mvScaleFactors[mvKeysRight[iR].octave];
        const int maxr = ceil(kpY + r);
        const int minr = floor(kpY - r);

        // 将特征点ir保证在可能的行号中
        for(int yi=minr;yi<=maxr;yi++)
            vRowIndices[yi].push_back(iR);
    }

    // 下面是 粗匹配 + 精匹配的过程
    // 对于立体矫正后的两张图,在列方向(x)存在最大视差maxd和最小视差mind
    // 也即是左图中任何一点p,在右图上的匹配点的范围为应该是[p - maxd, p - mind], 而不需要遍历每一行所有的像素
    // maxd = baseline * length_focal / minZ
    // mind = baseline * length_focal / maxZ

    const float minZ = mb;
    const float minD = 0;			// 最小视差为0,对应无穷远 
    const float maxD = mbf/minZ;    // 最大视差对应的距离是相机的基线

    // 保存sad块匹配相似度和左图特征点索引
    vector<pair<int, int> > vDistIdx;
    vDistIdx.reserve(N);

    // 为左图每一个特征点il,在右图搜索最相似的特征点ir
    for(int iL=0; iL<N; iL++) {

		const cv::KeyPoint &kpL = mvKeys[iL];
        const int &levelL = kpL.octave;
        const float &vL = kpL.pt.y;
        const float &uL = kpL.pt.x;

        // 获取左图特征点il所在行,以及在右图对应行中可能的匹配点
        const vector<size_t> &vCandidates = vRowIndices[vL];
        if(vCandidates.empty()) continue;

        // 计算理论上的最佳搜索范围
        const float minU = uL-maxD;
        const float maxU = uL-minD;
        
        // 最大搜索范围小于0,说明无匹配点
        if(maxU<0) continue;

		// 初始化最佳相似度,用最大相似度,以及最佳匹配点索引
        int bestDist = ORBmatcher::TH_HIGH;
        size_t bestIdxR = 0;
        const cv::Mat &dL = mDescriptors.row(iL);
        
        // Step 2. 粗配准。左图特征点il与右图中的可能的匹配点进行逐个比较,得到最相似匹配点的描述子距离和索引
        for(size_t iC=0; iC<vCandidates.size(); iC++) {

            const size_t iR = vCandidates[iC];
            const cv::KeyPoint &kpR = mvKeysRight[iR];

            // 左图特征点il与待匹配点ic的空间尺度差超过2,放弃
            if(kpR.octave<levelL-1 || kpR.octave>levelL+1)
                continue;

            // 使用列坐标(x)进行匹配,和stereomatch一样
            const float &uR = kpR.pt.x;

            // 超出理论搜索范围[minU, maxU],可能是误匹配,放弃
            if(uR >= minU && uR <= maxU) {

                // 计算匹配点il和待匹配点ic的相似度dist
                const cv::Mat &dR = mDescriptorsRight.row(iR);
                const int dist = ORBmatcher::DescriptorDistance(dL,dR);

				//统计最小相似度及其对应的列坐标(x)
                if( dist<bestDist ) {
                    bestDist = dist;
                    bestIdxR = iR;
                }
            }
        }
    
        // Step 3. 图像块滑动窗口用SAD(Sum of absolute differences,差的绝对和)实现精确匹配. 
        if(bestDist<thOrbDist) {
            // 如果刚才匹配过程中的最佳描述子距离小于给定的阈值
            // 计算右图特征点x坐标和对应的金字塔尺度
            const float uR0 = mvKeysRight[bestIdxR].pt.x;
            const float scaleFactor = mvInvScaleFactors[kpL.octave];
            
            // 尺度缩放后的左右图特征点坐标
            const float scaleduL = round(kpL.pt.x*scaleFactor);			
            const float scaledvL = round(kpL.pt.y*scaleFactor);
            const float scaleduR0 = round(uR0*scaleFactor);

            // 滑动窗口搜索, 类似模版卷积或滤波
            // w表示sad相似度的窗口半径
            const int w = 5;

            // 提取左图中,以特征点(scaleduL,scaledvL)为中心, 半径为w的图像块patch
            cv::Mat IL = mpORBextractorLeft->mvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduL-w,scaleduL+w+1);
            IL.convertTo(IL,CV_32F);
            
            // 图像块均值归一化,降低亮度变化对相似度计算的影响
			IL = IL - IL.at<float>(w,w) * cv::Mat::ones(IL.rows,IL.cols,CV_32F);

			//初始化最佳相似度
            int bestDist = INT_MAX;

			// 通过滑动窗口搜索优化,得到的列坐标偏移量
            int bestincR = 0;

			//滑动窗口的滑动范围为(-L, L)
            const int L = 5;

			// 初始化存储图像块相似度
            vector<float> vDists;
            vDists.resize(2*L+1); 

            // 计算滑动窗口滑动范围的边界,因为是块匹配,还要算上图像块的尺寸
            // 列方向起点 iniu = r0 - 最大窗口滑动范围 - 图像块尺寸
            // 列方向终点 eniu = r0 + 最大窗口滑动范围 + 图像块尺寸 + 1
            // 此次 + 1 和下面的提取图像块是列坐标+1是一样的,保证提取的图像块的宽是2 * w + 1
            // ! 源码: const float iniu = scaleduR0+L-w; 错误
            // scaleduR0:右图特征点x坐标
            const float iniu = scaleduR0-L-w;
            const float endu = scaleduR0+L+w+1;

			// 判断搜索是否越界
            if(iniu<0 || endu >= mpORBextractorRight->mvImagePyramid[kpL.octave].cols)
                continue;

			// 在搜索范围内从左到右滑动,并计算图像块相似度
            for(int incR=-L; incR<=+L; incR++) {

                // 提取右图中,以特征点(scaleduL,scaledvL)为中心, 半径为w的图像快patch
                cv::Mat IR = mpORBextractorRight->mvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduR0+incR-w,scaleduR0+incR+w+1);
                IR.convertTo(IR,CV_32F);
                
                // 图像块均值归一化,降低亮度变化对相似度计算的影响
                IR = IR - IR.at<float>(w,w) * cv::Mat::ones(IR.rows,IR.cols,CV_32F);
                
                // sad 计算,值越小越相似
                float dist = cv::norm(IL,IR,cv::NORM_L1);

                // 统计最小sad和偏移量
                if(dist<bestDist) {
                    bestDist = dist;
                    bestincR = incR;
                }

                //L+incR 为refine后的匹配点列坐标(x)
                vDists[L+incR] = dist; 	
            }

            // 搜索窗口越界判断
            if(bestincR==-L || bestincR==L)
                continue;

			// Step 4. 亚像素插值, 使用最佳匹配点及其左右相邻点构成抛物线来得到最小sad的亚像素坐标
            // 使用3点拟合抛物线的方式,用极小值代替之前计算的最优是差值
            //    \                 / <- 由视差为14,15,16的相似度拟合的抛物线
            //      .             .(16)
            //         .14     .(15) <- int/uchar最佳视差值
            //              . 
            //           (14.5)<- 真实的视差值
            //   deltaR = 15.5 - 16 = -0.5
            // 公式参考opencv sgbm源码中的亚像素插值公式
            // 或论文<<On Building an Accurate Stereo Matching System on Graphics Hardware>> 公式7

            const float dist1 = vDists[L+bestincR-1];	
            const float dist2 = vDists[L+bestincR];
            const float dist3 = vDists[L+bestincR+1];
            const float deltaR = (dist1-dist3)/(2.0f*(dist1+dist3-2.0f*dist2));

            // 亚像素精度的修正量应该是在[-1,1]之间,否则就是误匹配
            if(deltaR<-1 || deltaR>1)
                continue;
            
            // 根据亚像素精度偏移量delta调整最佳匹配索引
            float bestuR = mvScaleFactors[kpL.octave]*((float)scaleduR0+(float)bestincR+deltaR);
            float disparity = (uL-bestuR);
            if(disparity>=minD && disparity<maxD) {
                // 如果存在负视差,则约束为0.01
                if( disparity <=0 ) {
                    disparity=0.01;
                    bestuR = uL-0.01;
                }
                
                // 根据视差值计算深度信息
                // 保存最相似点的列坐标(x)信息
                // 保存归一化sad最小相似度
                // Step 5. 最优视差值/深度选择.
                mvDepth[iL]=mbf/disparity;
                mvuRight[iL] = bestuR;
                vDistIdx.push_back(pair<int,int>(bestDist,iL));
        }   
    }
    }
    // Step 6. 删除离群点(outliers)
    // 块匹配相似度阈值判断,归一化sad最小,并不代表就一定是匹配的,比如光照变化、弱纹理、无纹理等同样会造成误匹配
    // 误匹配判断条件  norm_sad > 1.5 * 1.4 * median
    sort(vDistIdx.begin(),vDistIdx.end());
    const float median = vDistIdx[vDistIdx.size()/2].first;
    const float thDist = 1.5f*1.4f*median;

    for(int i=vDistIdx.size()-1;i>=0;i--) {
        if(vDistIdx[i].first<thDist)
            break;
        else {
			// 误匹配点置为-1,和初始化时保持一直,作为error code
            mvuRight[vDistIdx[i].second]=-1;
            mvDepth[vDistIdx[i].second]=-1;
        }
    }
}

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/873095.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

centos7 nginx1.18.0离线升级至1.25.1

centos7 nginx1.18.0离线升级至1.25.1 项目背景 系统&#xff1a;centos 7 nginx版本&#xff1a; 1.18.0 最近护网行动查出来 有关Nginx的几个安全漏洞&#xff0c;解决方案只需要更新Nginx版本到最新即可。 Nginx升级过程 1. 下载新版本nginx 下载地址&#xff1a;https:…

【0.2】lubancat鲁班猫4远程ubuntu22.04.2 无需任何安装

环境 lubancat4鲁班猫4 (4G0)不带emmc 系统镜像ubuntu-22.04.2-desktop-arm64-lubancat-4.img 网络环境:有线网络与本win10电脑同意环境 操作步骤ubuntu正常开机登陆用户&#xff0c;连接好网络进入设置>网络查看设备当前局域网IP 如192.168.199.159进入设置>共享>远程…

MAUI+Blazor:隐藏标题栏和问题

文章目录 前言相关文章代码问题有必要解决吗&#xff1f; 前言 最近在研究MAUIBlazor开发&#xff0c;发现一个问题&#xff0c;原生的的标题栏实在是太丑了。 相关文章 MAUI桌面端标题栏设置和窗口调整 MAUI Windows How to completely hide the TitleBar? #15142 MAUI …

Actuator微服务信息完善-Eureka—SpringCloud(版)微服务学习教程(11)

一、Actuator是什么&#xff1f; Actuator是Springboot提供的用来对应用系统进行自省和监控的功能模块&#xff0c;借助于Actuator开发者可以很方便地对应用系统某些监控指标进行查看、统计等。 在Springboot中使用Actuator监控非常简单&#xff0c;只需要在工程POM文件中引入…

Unity 射线检测

文章目录 1. 定义2. 重要类和方法2.1 Ray2.2 从屏幕发出射线&#xff1a;2.3 Raycast2.4 RaycastAll2.5 RaycastHit 碰撞信息2.6 layerMask 让射线检测只检测指定层级的对象 1. 定义 在Unity中&#xff0c;射线检测&#xff08;Raycasting&#xff09;是一种常用的技术&#x…

计网第一章

注意&#xff1a;计网知识点十分多&#xff0c;在本篇及后续博客主要记录个人认为比较重要的知识点。 1.计算机网络的基本概念 计算机网络就是自治的计算机互连起来的集合。计算机网络可以简称为网络&#xff0c;而互连网就是把许多网络连接起来&#xff0c;即网络的网络。 …

Linux发行版连接数位板手写板以后映射方向不对?

首先查看连接的设备&#xff1a; xinput list 如果像下图这样&#xff0c;鼠标类设备里面没有&#xff0c;只有键盘设备里面有你的数位板&#xff0c;那你就拿着笔到数位板上面比划比划&#xff0c;然后点一点笔上的按键&#xff0c;这样就能识别笔和按住按钮时候橡皮了。 比划…

每期一个小窍门: 玩转go mod 命令

看完本期小窍门 你将学会 go下载/更新 包的命令如何挎包调用/路径名称约定init()函数的作用和一些细节 本文涉及到的目录结构如下 关于 go.mod go.sum 这个demo依赖 github.com/bytedance/sonic 可以使用下面两个命令来确保依赖正常加载 go get github.com/bytedance/son…

【5G 核心网】5G 多PDU会话锚点技术介绍

博主未授权任何人或组织机构转载博主任何原创文章&#xff0c;感谢各位对原创的支持&#xff01; 博主链接 本人就职于国际知名终端厂商&#xff0c;负责modem芯片研发。 在5G早期负责终端数据业务层、核心网相关的开发工作&#xff0c;目前牵头6G算力网络技术标准研究。 博客…

HRS--人力资源系统(Springboot+vue)(一)配置环境--登录篇

原谅我的三心二意&#xff0c;心血来潮写一个人力资源系统练练手 一上来就报错&#xff0c;老天待我不薄&#xff0c;手中拳头紧握。。。 问题一&#xff1a;这个错误头疼&#xff0c;推测是因为用了是新建的springboot maven项目是springboot3.0以上要jdk17以上等导致的&#…

Labview解决“重置VI:xxx.vi”报错问题

文章目录 前言一、程序框图二、前面板三、问题描述四、解决办法 前言 在程序关闭前面板的时候小概率型出现了 重置VI&#xff1a;xxx.vi 这个报错&#xff0c;并且发现此时只能通过任务管理器杀掉 LabVIEW 进程才能退出&#xff0c;这里介绍一下解决方法。 一、程序框图 程序…

连接不上手机,adb devices为空:

首先说明一下&#xff0c;我是已经安装了android studio,也配置了环境变量&#xff0c;但是还是连接不上手机 解决方案&#xff1a; 1.打开开发者模式 https://product.pconline.com.cn/itbk/sjtx/sjwt/1424/14246015.html 2.开启usb调试 https://baiyunju.cc/10770 最后成功…

Day 26 C++ list容器(链表)

文章目录 list基本概念定义结构双向迭代器优点缺点List和vector区别存储结构内存管理迭代器稳定性随机访问效率 list构造函数——创建list容器函数原型示例 list 赋值和交换函数原型 list 大小操作函数原型示例 list 插入和删除函数原型示例 list 数据存取函数原型注意示例 lis…

JVM——栈和堆概述,以及有什么区别?

方法栈 方法栈并不是某一个 JVM 的内存空间&#xff0c;而是我们描述方法被调用过程的一个逻辑概念。 在同一个线程内&#xff0c;T1()调用T2()&#xff1a; T1()先开始&#xff0c;T2()后开始&#xff1b;T2()先结束&#xff0c;T1()后结束。 堆和栈概述 从英文单词角度来…

【效率系列】简化繁杂表单数据处理,迅速增强办公数字化能力

写在前面 数据处理是数据分析的奠基石&#xff0c;只有使用处理干净的数据&#xff0c;分析才会产生价值。简单而言&#xff0c;数据处理的终极目的是将非结构化数据转换为结构化数据。 虽然数据处理自身未必直接产生数据价值&#xff0c;但其过程往往相当耗时&#xff0c;因此…

【Vue3-Router】历史记录

replace App.vue <template><h1>hello world</h1><div><!-- replace 不保存历史记录 --><router-link replace to"/">login</router-link><router-link replace style"margin-left: 10px;" to"/reg&q…

高效实用小工具之Everything

一&#xff0c;简介 有时候我们电脑文件较多时&#xff0c;想快速找到某个文件不是一件容易的事情&#xff0c;实用windows自带的搜素太耗时&#xff0c;效率不高。今天推荐一个用来搜索电脑文件的小工具——Everything&#xff0c;本文将介绍如何安装以及使用everything&…

Redis——三个特殊的数据类型+事务

概述 全称为远程字典服务。 Redis——基础篇(包含redis在云服务上的docker化安装和连接以及常用命令)_连接docker中的redis_北岭山脚鼠鼠的博客-CSDN博客 Redis能干什么&#xff1f; 1.内存存储、持久化&#xff0c;内存中是断电即失&#xff0c;因此持久化很重要&#xff…

C++ 虚继承

C棱形继承 在 C 中&#xff0c;在使用 多继承 时&#xff0c;如果发生了如果类 A 派生出类 B 和类 C&#xff0c;类 D 继承自类 B 和类 C&#xff0c;这时候就发生了菱形继承。 如果发生了菱形继承&#xff0c;这个时候类 A 中的 成员变量 和 成员函数 继承到类 D 中变成了两…

开源可商业运营的ChatGpt网页源码v1.2.2

&#x1f916; 主要功能 后台管理系统,可对用户,Token,商品,卡密等进行管理 精心设计的 UI&#xff0c;响应式设计 极快的首屏加载速度&#xff08;~100kb&#xff09; 支持Midjourney绘画和DALLE模型绘画,GPT4等应用 海量的内置 prompt 列表&#xff0c;来自中文和英文 一键导…