【地图构建(1)】占用栅格地图构建Occupancy grid mapping

本文主要参考Probabilistic Robotics《概率机器人》一书。
其他参考:
弗莱堡大学课件
博客
含代码博客

0.引言

位姿已知的地图构建(mapping with known poses)的定义:已知机器人的位姿 x 1 : t x_{1:t} x1:t和传感器的观测数据 z 1 : t z_{1:t} z1:t求解最可能的地图 m ∗ = arg ⁡ max ⁡ m P ( m ∣ x 1 : t , z 1 : t ) m^*=\arg\max_mP(m|x_{1:t},z_{1:t}) m=argmaxmP(mx1:t,z1:t)
占用栅格地图,顾名思义地图形式是栅格形式,即将环境分为小格子
在这里插入图片描述 m i m_i mi表示第i个栅格单元,占用栅格地图将空间分割为有限多个栅格地图 m = { m i } m=\{m_i\} m={mi},每个 m i m_i mi与一个二值占用变量相对应,该变量指示出该单元是否被占用,被占用设为1,未被占用设为0。 p ( m i ) p(m_i) p(mi)表示该栅格单元被占用的可能性。
为所有的栅格建立后验概率 p ( m i ∣ z 1 : t , x 1 : t ) p(m_i|z_{1:t},x_{1:t}) p(miz1:t,x1:t),那么构建地图公式变为
P ( m ∣ x 1 : t , z 1 : t ) = p ( m 1 , m 2 , . . . , m n ∣ x 1 : t , z 1 : t ) = ∑ i = 1 n p ( m i ∣ z 1 : t , x 1 : t ) (假设每个格子独立同分布) P(m|x_{1:t},z_{1:t})=p(m_1,m_2,...,m_n|x_{1:t},z_{1:t})\\ =\sum^n_{i=1}p(m_i|z_{1:t},x_{1:t}) (假设每个格子独立同分布) P(mx1:t,z1:t)=p(m1,m2,...,mnx1:t,z1:t)=i=1np(miz1:t,x1:t)(假设每个格子独立同分布)

但是这种独立同分布抛弃了相邻单元之间的联系,并不是最优解,对于这一点,我们暂且不讨论。

1. 静态二值贝叶斯滤波

上面这个独立同分布的地图构建公式可以看作一个静态二值贝叶斯滤波(binary Bayes filter)——不随时间变化的二值状态的最优估计问题。
对于一个格子被占有的概率记为——置信度 b e l ( m i ) = p ( m i ∣ x 1 : t , z 1 : t ) bel(m_i)=p(m_i|x_{1:t},z_{1:t}) bel(mi)=p(mix1:t,z1:t),最终通过设置阈值来确定哪些格子是占有栅格(例如 b e l ( m i ) > 0.6 bel(m_i)\gt0.6 bel(mi)>0.6),哪些是空闲栅格(例如 b e l ( m i ) < 0.4 bel(m_i)\lt0.4 bel(mi)<0.4),哪些是未知栅格( 0.4 ≤ b e l ( m i ) ≤ 0.6 0.4\le bel(m_i)\le0.6 0.4bel(mi)0.6)。
求解占有栅格的置信度:
b e l t ( m i ) = p ( m i ∣ z 1 : t , x 1 : t ) bel_t(m_i)=p(m_i|z_{1:t},x_{1:t}) belt(mi)=p(miz1:t,x1:t)
在这里插入图片描述
同理可得出空闲栅格的置信度
在这里插入图片描述利用两式相除消去部分未知部分:
在这里插入图片描述在这里插入图片描述二值Bayes滤波递归更新公式 l t , i = l t − 1 , i + l i n v , i − l 0 l_{t,i}=l_{t-1,i}+l_{inv,i}-l_0 lt,i=lt1,i+linv,il0,更新后在求置信度:
b e l t m i = 1 − 1 1 + exp ⁡ ( l t , i ) bel_t{m_i}=1-\frac{1}{1+\exp(l_{t,i})} beltmi=11+exp(lt,i)1
初始时刻栅格的占用情况未知,将其置信度设为 b e l 0 ( m i ) = 0.5 bel_0(m_i)=0.5 bel0(mi)=0.5,则先验概率 l 0 = 0 l_0=0 l0=0
在这里插入图片描述

2.反演测量模型

2.1 声纳模型

来自PR一书和弗莱堡大学ppt中的模型,当某一个测量点距离为z,分别设置了z-d1,z+d1,z+d2,z+d3的占据概率。其中0-(z-d1)为free,(z-d1)-(z+d3)为occ,(z+d3)之后为no info。
在这里插入图片描述

2.2激光传感器模型

在这里插入图片描述

#include <occ_grid_mapping/grid_mapper.h>

GridMapper::GridMapper ( GridMap* map, Pose2d& T_r_l, double& P_occ, double& P_free, double& P_prior):
map_(map), T_r_l_(T_r_l), P_occ_(P_occ), P_free_(P_free), P_prior_(P_prior){}

void GridMapper::updateMap ( const sensor_msgs::LaserScanConstPtr& scan,  Pose2d& robot_pose )
{
    /* 获取激光的信息 */
    const double& ang_min = scan->angle_min;        //雷达起始角度
    const double& ang_max = scan->angle_max;        //雷达终止角度
    const double& ang_inc = scan->angle_increment;  //角度增量(角度分辨率)
    const double& range_max = scan->range_max;      //雷达数据的最小值
    const double& range_min = scan->range_min;      //雷达数据的最大值
    
    /* 设置遍历的步长,沿着一条激光线遍历 */
    const double& cell_size = map_->getCellSize();
    const double inc_step = 1.0 * cell_size;

    /* for every laser beam */
    for(size_t i = 0; i < scan->ranges.size(); i ++)
    {
        /* 获取当前beam的距离 */
        double R = scan->ranges.at(i); 
        if(R > range_max || R < range_min)
            continue;
        
        /* 沿着激光射线以inc_step步进,更新地图*/
        double angle = ang_inc * i + ang_min;
        double cangle = cos(angle);
        double sangle = sin(angle);
        Eigen::Vector2d last_grid(Eigen::Infinity, Eigen::Infinity); //上一步更新的grid位置,防止重复更新
        for(double r = 0; r < R + cell_size; r += inc_step)
        {
            Eigen::Vector2d p_l(
                r * cangle,
                r * sangle
            ); //在激光雷达坐标系下的坐标
            
            /* 转换到世界坐标系下 */
            Pose2d laser_pose = robot_pose * T_r_l_;
            Eigen::Vector2d p_w = laser_pose * p_l;

            /* 更新这个grid */
            if(p_w == last_grid) //避免重复更新
                continue;
            
            updateGrid(p_w, laserInvModel(r, R, cell_size));    //更新占据概率
            	    
            last_grid = p_w;
        }//for each step
    }// for each beam
}

void GridMapper::updateGrid ( const Eigen::Vector2d& grid, const double& pmzx )
{
    /* TODO 这个过程写的太低效了 */
    double log_bel;
    if(  ! map_->getGridLogBel( grid(0), grid(1), log_bel )  ) //获取log的bel
        return;
    log_bel += log( pmzx / (1.0 - pmzx) ); //更新
    map_->setGridLogBel( grid(0), grid(1), log_bel  ); //设置回地图
}

//雷达的反演测量模型
double GridMapper::laserInvModel ( const double& r, const double& R, const double& cell_size )
{
    if(r < ( R - 0.5*cell_size) )
        return P_free_;
    
    if(r > ( R + 0.5*cell_size) )
        return P_prior_;
    
    return P_occ_;
}

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

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

云原生(六)、CICD - Jenkins快速入门

Jenkuns快速入门 一、CICD概述 CICD是持续集成&#xff08;Continuous Integration&#xff09;和持续部署&#xff08;Continuous Deployment&#xff09;的缩写。它是软件开发中的一种流程和方法论&#xff0c;旨在通过自动化的方式频繁地将代码集成到共享存储库中&#xf…

zotero+word优化管理参考文献

写论文&#xff0c;整理参考文献&#xff0c;管理参考文献很麻烦&#xff0c;参考文献格式罗列很麻烦&#xff0c;论文需要修改时&#xff0c;重新调整参考文献顺序很麻烦。 zoteroword可以很好的帮助解决这个问题。 Step1 zotero软件安装 默认word你已经安装好了 step2 安…

线程局部存储(TLS)

线程局部存储&#xff08;Thread Local Storage&#xff0c;TLS&#xff09;&#xff0c;是一种变量的存储方法&#xff0c;这个变量在它所在的线程内是全局可访问的&#xff0c;但是不能被其他线程访问到&#xff0c;这样就保持了数据的线程独立性。而熟知的全局变量&#xff…

班级综合测评管理系统的设计与实现|Springboot+ Mysql+Java+ B/S结构(可运行源码+数据库+设计文档)

本项目包含可运行源码数据库LW&#xff0c;文末可获取本项目的所有资料。 推荐阅读100套最新项目持续更新中..... 2024年计算机毕业论文&#xff08;设计&#xff09;学生选题参考合集推荐收藏&#xff08;包含Springboot、jsp、ssmvue等技术项目合集&#xff09; 目录 1. …

二十 超级数据查看器 讲解稿 功能概述

二十 超级数据查看器 讲解稿 功能概述 ​ ​​点击此处 以新页面 打开B站 播放当前教学视频 点击访问app下载页面 豌豆荚 下载地址​ ​ 讲解稿 ​ 界面启动 ​ 导入 ​ 选excel文件 导入 ​ 原来的excel文件 ​ 导入进本地数据库sqlite ​ 导入成功 ​ 列…

MySQL---事务

目录 一、事务简介 二、事务操作 1.未控制事务 2.事务控制一 3.控制事务二 三、事务的四大特性 四、并发事务问题 五、事务隔离级别 一、事务简介 事务 是一组操作的集合&#xff0c;它是一个不可分割的工作单位&#xff0c;事务会把所有的操作作为一个整体一起向系统提交或…

喜讯!聚铭网络荣获《日志分类方法及系统》发明专利

近日&#xff0c;聚铭网络又喜获一项殊荣&#xff0c;其申报的《日志分类方法及系统》发明专利成功获得国家知识产权局的授权&#xff0c;正式荣获国家发明专利证书。 在信息化时代&#xff0c;网络安全问题日益凸显&#xff0c;日志分析作为保障网络安全的重要手段&#xff…

【嵌入式——C语言】VScode编写C程序、交叉编译

【嵌入式——C语言】VScode编写C程序、交叉编译 第一步第二步第三步第四步第五步第六步第七步第八步 第一步 下载Visual Studio Code下载地址 然后直接安装就可以了。 第二步 前提是你的电脑上安装了WSL。。。 打开vscode的扩展&#xff0c;输入WSL进行安装 安装完之后在窗…

【深度学习】图片预处理,分辨出模糊图片

ref:https://pyimagesearch.com/2015/09/07/blur-detection-with-opencv/ 论文 ref:https://www.cse.cuhk.edu.hk/leojia/all_final_papers/blur_detect_cvpr08.pdf 遇到模糊的图片&#xff0c;还要处理一下&#xff0c;把它挑出来&#xff0c;要么修复&#xff0c;要么弃用。否…

vue组件如何使用?

今天我随便试两个组件 第一个轮播图 在minn.js 引入 import { createApp } from vue; import { Swipe, SwipeItem } from vant; const app createApp(); app.use(Swipe); app.use(SwipeItem); <van-swipe class"my-swipe" :autoplay"3000" indica…

uniapp 微信小程序 canvas 手写板文字重复倾斜水印

核心逻辑 先将坐标系中心点通过ctx.translate(canvasw / 2, canvash / 2) 平移到canvas 中心&#xff0c;再旋转设置水印 假如不 translate 直接旋转&#xff0c;则此时的旋转中心为左上角原点&#xff0c;此时旋转示意如图所示 当translate到中心点之后再旋转&#xff0c;此…

逐步学习Go-协程goroutine

参考&#xff1a;逐步学习Go-协程goroutine – FOF编程网 什么是线程&#xff1f; 简单来说线程就是现代操作系统使用CPU的基本单元。线程基本包括了线程ID&#xff0c;程序计数器&#xff0c;寄存器和线程栈。线程共享进程的代码区&#xff0c;数据区和操作系统的资源。 线…

每日一题--- 环形链表[力扣][Go]

环形链表 题目&#xff1a;142. 环形链表 II 给定一个链表的头节点 head &#xff0c;返回链表开始入环的第一个节点。 如果链表无环&#xff0c;则返回 null。 如果链表中有某个节点&#xff0c;可以通过连续跟踪 next 指针再次到达&#xff0c;则链表中存在环。 为了表示给…

数字身份的革命:解锁 Web3 的身份验证技术

引言 随着数字化时代的到来&#xff0c;个人身份认证成为了日常生活和商业活动中不可或缺的一部分。传统的身份验证方式存在着安全性低、易伪造、不便利等问题&#xff0c;因此&#xff0c;人们迫切需要一种更安全、更便捷的身份验证技术。在这样的背景下&#xff0c;Web3的身…

数仓建设实践——58用户画像数仓建设

目录 一、数据仓库&用户画像简介 1.1 数据仓库简介 1.2 数据仓库的价值 1.3 用户画像简介 1.4 用户画像—标签体系 二、用户画像数仓建设过程 2.1 画像数仓—背景&现状 2.2 画像数仓—整体架构 2.3 画像数仓—研发流程 2.4 画像数仓—指标定义 2.5 画像数仓…

Java基本数据结构(基于jdk11)

java中有很多数据类型&#xff0c;以下数据类型都出于java.util包下且日常经常使用的&#xff0c;先介绍一下接口&#xff0c;接口可以很快的了解到这个数据结构的特性。 接口 List: 有序队列&#xff0c;如&#xff1a;ArrayList、LinkedList Deque&#xff1a;双端队列&am…

视图的作用

目录 视图的作用 创建视图 为 scott 分配创建视图的权限 查询视图 复杂视图的创建 视图更新的限制问题 更新视图中数据的部门编号&#xff08;视图的存在条件&#xff09; 限制通过视图修改数据表内容 创建只读的视图 复杂视图创建 oracle从入门到总裁:​​​​​​h…

Android 性能优化(六):启动优化的详细流程

书接上文&#xff0c;Android 性能优化&#xff08;一&#xff09;&#xff1a;闪退、卡顿、耗电、APK 从用户体验角度有四个性能优化方向&#xff1a; 追求稳定&#xff0c;防止崩溃追求流畅&#xff0c;防止卡顿追求续航&#xff0c;防止耗损追求精简&#xff0c;防止臃肿 …

【研发日记】Matlab/Simulink开箱报告(十)——Signal Routing模块模块

文章目录 前言 Signal Routing模块 虚拟模块和虚拟信号 Mux和Demux Vector Concatenate和Selector Bus Creator和Bus Selector 分析和应用 总结 前言 见《开箱报告&#xff0c;Simulink Toolbox库模块使用指南&#xff08;五&#xff09;——S-Fuction模块(C MEX S-Fun…

SQLite中的动态内存分配(五)

返回&#xff1a;SQLite—系列文章目录 上一篇&#xff1a;SQLite中的原子提交&#xff08;四&#xff09; 下一篇&#xff1a;SQLite使用的临时文件&#xff08;二&#xff09; ​概述 SQLite使用动态内存分配来获得 用于存储各种对象的内存 &#xff08;例如&#xff1a…
最新文章