三维pcd地图转二维栅格地图

article/2025/5/17 23:44:08

1.概述

在使用导航时,通常会根据二维栅格地图做路径规划,需要将三维点云地图转化成栅格地图。
本文采用滤波及投影的方法,
主要步骤包括

  • 对输入点云进行直通滤波,获取限定高度范围的数据
  • 在进行半径滤波,去除部分孤立点
  • 转换为栅格地图

2.方法说明

完整程序代码:github

运行方法:
下载编译后,

mkdir -p test_ws/src&& cd test_ws/src
git clone -b develop  https://github.com/Hinson-A/pcd2pgm_package
cd ../
catkin_make

编译完成后,查看 src/pcd2pgm_package/pcd2pgm/launch/中的run.launch文件,修改相应的文件路径及名称

launch文件如下

<!-- -->
<launch>
<node pkg="pcd2pgm" name="pcd2pgm" type="pcd2pgm" output="screen">
<!-- 存放pcd文件的路径-->
<param name="file_directory" value= "/home/robot/map/" />
<!-- pcd文件名称-->
<param name="file_name" value= "map" />
<!-- 选取的范围 最小的高度-->
<param name="thre_z_min" value= "0.1" />
<!-- 选取的范围 最大的高度-->
<param name="thre_z_max" value= "1.5" />
<!--0 选取高度范围内的,1选取高度范围外的-->
<param name="flag_pass_through" value= "0" />
<!-- 半径滤波的半径-->
<param name="thre_radius" value= "0.5" />
<!-- 半径滤波的要求点数个数-->
<param name="thres_point_count" value= "10" />
<!-- 存储的栅格map的分辨率-->
<param name="map_resolution" value= "0.05" />
<!-- 转换后发布的二维地图的topic,默认使用map即可,可使用map_server保存-->
<param name="map_topic_name" value= "map" />
</node></launch>

修改完成后,运行程序

roslaun run.launch

在这里插入图片描述
此时,通过map_server 保存该栅格地图

rosrun map_server map_saver

生成对应的map文件
在这里插入图片描述
同时在原pcd文件夹下,也保存了直通滤波和半径滤波后的pcd文件。

原图:
在这里插入图片描述
直通滤波:
在这里插入图片描述
半径滤波:
在这里插入图片描述
二维栅格地图
在这里插入图片描述

3.关键程序解析

3.1 获取pcd文件

  // 下载pcd文件if (pcl::io::loadPCDFile<pcl::PointXYZ>(pcd_file, *pcd_cloud) == -1) {PCL_ERROR("Couldn't read file: %s \n", pcd_file.c_str());return (-1);}

3.2 进行直通滤波

指定字段,指定坐标范围进行裁剪。可以选择保留范围内的点或者范围外的点。
这里滤出设置范围之外的点云数据

//直通滤波器对点云进行过滤,获取设定高度范围内的数据
void PassThroughFilter(const double &thre_low, const double &thre_high,const bool &flag_in) {// 创建滤波器对象pcl::PassThrough<pcl::PointXYZ> passthrough;//输入点云passthrough.setInputCloud(pcd_cloud);//设置对z轴进行操作passthrough.setFilterFieldName("z");//设置滤波范围passthrough.setFilterLimits(thre_low, thre_high);// true表示保留滤波范围外,false表示保留范围内passthrough.setFilterLimitsNegative(flag_in);//执行滤波并存储passthrough.filter(*cloud_after_PassThrough);// test 保存滤波后的点云到文件pcl::io::savePCDFile<pcl::PointXYZ>(file_directory + "map_filter.pcd",*cloud_after_PassThrough);std::cout << "直通滤波后点云数据点数:"<< cloud_after_PassThrough->points.size() << std::endl;
}

3.3 进行半径滤波

半径滤波说明:
点云半径滤波也叫基于连通分析的点云滤波,该方法的基本思想是:假定原始点云中每个激光点在指定的半径邻域中至少包含一定数量的近邻点。原始点云中符合假设条件的激光点被视为正常点进行保留,反之,则视为噪声点并进行去除。
该方法对原始激光点云中存在的一些悬空的孤立点或无效点具有很好的去除效果。

//半径滤波
void RadiusOutlierFilter(const pcl::PointCloud<pcl::PointXYZ>::Ptr &pcd_cloud0,const double &radius, const int &thre_count) {//创建滤波器pcl::RadiusOutlierRemoval<pcl::PointXYZ> radiusoutlier;//设置输入点云radiusoutlier.setInputCloud(pcd_cloud0);//设置半径,在该范围内找临近点radiusoutlier.setRadiusSearch(radius);//设置查询点的邻域点集数,小于该阈值的删除radiusoutlier.setMinNeighborsInRadius(thre_count);radiusoutlier.filter(*cloud_after_Radius);// test 保存滤波后的点云到文件pcl::io::savePCDFile<pcl::PointXYZ>(file_directory + "map_radius_filter.pcd",*cloud_after_Radius);std::cout << "半径滤波后点云数据点数:" << cloud_after_Radius->points.size()<< std::endl;
}

3.4 发布map

转换为栅格地图数据并发布

//转换为栅格地图数据并发布
void SetMapTopicMsg(const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,nav_msgs::OccupancyGrid &msg) {msg.header.seq = 0;msg.header.stamp = ros::Time::now();msg.header.frame_id = "map";msg.info.map_load_time = ros::Time::now();msg.info.resolution = map_resolution;double x_min, x_max, y_min, y_max;double z_max_grey_rate = 0.05;double z_min_grey_rate = 0.95;//? ? ??double k_line =(z_max_grey_rate - z_min_grey_rate) / (thre_z_max - thre_z_min);double b_line =(thre_z_max * z_min_grey_rate - thre_z_min * z_max_grey_rate) /(thre_z_max - thre_z_min);if (cloud->points.empty()) {ROS_WARN("pcd is empty!\n");return;}for (int i = 0; i < cloud->points.size() - 1; i++) {if (i == 0) {x_min = x_max = cloud->points[i].x;y_min = y_max = cloud->points[i].y;}double x = cloud->points[i].x;double y = cloud->points[i].y;if (x < x_min)x_min = x;if (x > x_max)x_max = x;if (y < y_min)y_min = y;if (y > y_max)y_max = y;}// origin的确定msg.info.origin.position.x = x_min;msg.info.origin.position.y = y_min;msg.info.origin.position.z = 0.0;msg.info.origin.orientation.x = 0.0;msg.info.origin.orientation.y = 0.0;msg.info.origin.orientation.z = 0.0;msg.info.origin.orientation.w = 1.0;//设置栅格地图大小msg.info.width = int((x_max - x_min) / map_resolution);msg.info.height = int((y_max - y_min) / map_resolution);//实际地图中某点坐标为(x,y),对应栅格地图中坐标为[x*map.info.width+y]msg.data.resize(msg.info.width * msg.info.height);msg.data.assign(msg.info.width * msg.info.height, 0);ROS_INFO("data size = %d\n", msg.data.size());for (int iter = 0; iter < cloud->points.size(); iter++) {int i = int((cloud->points[iter].x - x_min) / map_resolution);if (i < 0 || i >= msg.info.width)continue;int j = int((cloud->points[iter].y - y_min) / map_resolution);if (j < 0 || j >= msg.info.height - 1)continue;// 栅格地图的占有概率[0,100],这里设置为占据msg.data[i + j * msg.info.width] = 100;//    msg.data[i + j * msg.info.width] = int(255 * (cloud->points[iter].z *//    k_line + b_line)) % 255;}
}

reference pcd转pgm/3d点云转2d灰度图


http://chatgpt.dhexx.cn/article/BcSgpgl7.shtml

相关文章

【python数据处理】替代Excel三维地图依据经纬度坐标的绘制热力地图的方式

替代Excel三维地图依据经纬度坐标的绘制热力地图的方式 背景pyecharts绘制 背景 由于某人访问了某地&#xff0c;即便是调整电脑中的区域为别的国家或者地区时候&#xff0c;excel三维地图选择时候依然会弹出很抱歉&#xff0c;三维地图当前不在你的国家/地区使用。这个“当前…

三维地图3D可视化应用案例

1、如何搭建离线地图开发环境 2、下载离线地图数据(金字塔瓦片数据&#xff09; 3、下载离线地图地形数据库&#xff08;实现地表高低起伏&#xff09; 4、添加离线地图数据到本地服务器 &#xff08;含3D&#xff09; 5、离线地图二次开发接口&#xff08;离线地图API&#…

BlenderGIS生成三维地图白模

目录 简介安装配置处理选点建模后记 简介 BlenderBlenderGISOpenTopography 可以实现地图选点并获取对应三维白模 安装 安装 blender&#xff08;版本不要太新&#xff0c;我用的是 3.0&#xff09;&#xff1a;https://www.blender.org/download/ 获取 blender-gis&#xf…

很抱歉,三维地图当前不能在你的国家/地区使用 Excel绘制三维地图问题解决

手动反爬虫&#xff1a;原博地址 https://blog.csdn.net/lys_828/article/details/123585838 知识梳理不易&#xff0c;请尊重劳动成果&#xff0c;文章仅发布在CSDN网站上&#xff0c;在其他网站看到该博文均属于未经作者授权的恶意爬取信息问题 之前在利用Excel进行三维地图…

MATLAB绘制三维地图

1、meshgrid&#xff1a;生成格点矩阵&#xff0c;类似于给定坐标空间 [x,y]meshgrid(1:10); 2、interp插值法 插值法又称“内插法”&#xff0c;是利用函数f (x)在某区间中已知的若干点的函数值&#xff0c;作出适当的特定函数&#xff0c;在区间的其他点上用这特定函数的值作…

说说基于BS架构的三维地图引擎如arcgis以及三维引擎cesium等在数字孪生三维可视化项目中踩过的那些坑

不知从何年何月BS架构的系统在PC端领域占据了大半壁江山&#xff0c;众多的软件公司为了迎合客户&#xff0c;在项目中纷纷采用BS架构&#xff0c;也因此导致培养了一大批相应的程序员技术人才。 然而&#xff0c;在移动端、手机领域&#xff0c;却又出现另一番景象&#…

ESMap三维地图开发流程

易景地图&#xff08;ESMap&#xff09;是一款三维地图在线开发平台&#xff0c;常被用来做智慧城市数据可视化的在线快速开发&#xff0c;广泛应用于室内外定位导航和数字孪生技术场景。下面就简单介绍一下ESMap三维地图的开发流程&#xff1a; 一、场景搭建 进入官网&#…

html加载三维地图,Cesium加载三维地形及WMS地图,并实现动态控制显示

写在前面: 本次工程主要实现的是cesium基础三维地形加载、视角控制、经纬度显示;重点是实现cesium加载wms图层,并对wms图层进行参数更新,实现动态控制,进一步实现时间地图的展示目的。为时间地图可视化提供了三维显示的思路。中间进行参数控制的时候,需要销毁provider,目…

实景三维数据也可以免费下载

之前分享过不少影像&#xff0c;矢量、DEM…数据下载方法。 随着实景三维的火热&#xff0c;一些实景三维数据可以免费下载吗&#xff1f; 有&#xff01;但可下载的真的不多… 今天我们就来看看怎么才能下载到免费的实景三维数据。 全国地理信息资源目录服务系统 https://…

ArcScene:构建三维地图

主要介绍一下使用ArcScene来制作三维地图&#xff0c;下面是主要的步骤 1.打开ArcGIS下面的ArcScene&#xff0c;将研究区域的DEM和矢量边界数据添加进来&#xff1a; 2.右键DEM&#xff0c;点击属性->基本高度&#xff0c;选择“在自定义表面上浮动”&#xff0c;该路径选…

【Echarts】三维地图叠加柱状图

代码如下所示&#xff1a; <!DOCTYPE html> <html lang"en"> <head><meta http-equiv"Content-Type" content"text/html; charsetGBK" /><title>echarts 地图</title><script src"https://cdn.sta…

三维地图可视化应用教程

1、如何搭建离线地图开发环境 2、下载离线地图数据(金字塔瓦片数据&#xff09; 3、下载离线地图地形数据库&#xff08;实现地表高低起伏&#xff09; 4、添加离线地图数据到本地服务器 &#xff08;含3D&#xff09; 5、离线地图二次开发接口&#xff08;离线地图API&#…

三维地图看世界

随着当今社会的不断发展&#xff0c;人们的需求以及对效率质量的要求也在不断提高。城市建设也越来越密集&#xff0c;城市规划要求越来越高&#xff0c;城市管理中对人流、车流的控制也越来越精细&#xff0c;地图作为记录地理信息的一种图形语言形式&#xff0c;不仅为人们的…

三维地图下载,3D地图下载,谷歌地球三维地形图查看

更多示例代码&#xff1a;http://www.bigemap.com/offlinemaps/gl.html 3D地球依据高程数据等对地表进行渲染&#xff0c;实现地表的起伏&#xff0c;模拟出真实的三维场景&#xff0c;让你有如身临其境般的感觉。 &#xff08;注&#xff1a;Bigemap 3D地球是一个三维地图浏览…

关于如何下载E都市三维地图的教程

原文转载&#xff1a;http://www.arceyes.com/bbs/thread-18338-1-1.html 下载安装水经注E都市三维地图下载器&#xff0c;如果你没有安装&#xff0c;请百度“水经注软件”到官网下载。 软件安装后&#xff0c;启动界面如下图所示。 在软件的左边列出了可以下载E都市三维地图…

主题 10:如何将工作中的创新点转化为专利

1. 引言 很多工程师有技术情怀,在工作中也很注重用新方法、新思路解决问题,但却很少将工作中的创新转化为专利,无形中错失了进一步创造价值的机会。 专利的价值是多方面的,专利储备数量在一定程度上可以反映企业的技术实力;通过专利授权、转让可以带来可观的经济效益;专…

来自创新之国以色列的 Emerge 基金会给中国带来什么?

当创新和实干深入整个民族的血液&#xff0c;人口小国成为创新大国也就不足为奇了。 7 月 20 日&#xff0c;以色列风投公司 Emerge 在北京召开了新基金 Emerge Fund II 的主题发布会——以色列&#xff1a;创新国度的创新尖兵&#xff0c;发布会上&#xff0c;前以色列首席科学…

2023亚马逊云科技中国峰会引领无服务器架构新潮流:Serverlesspresso Workshop

序言 在今年3月&#xff0c;我有幸接触了一个项目&#xff0c;也因此结识了 亚马逊云科技无服务器架构 Serverless。在陆续了解 Amazon 产品的过程中&#xff0c;我逐渐发现它所带给我的惊喜远远超出了最初的预期。 今天&#xff0c;想向大家介绍一个名为 Serverlesspresso Wor…

Peter Thiel认为中国科技产业不值得投资

近些年硅谷对中国的关注一直在增加。不仅越来越多的科技公司开始进入中国&#xff0c;很多投资人也开始对中国创业公司表现出兴趣。这些人里一部分仅仅对中国感兴趣&#xff0c;还有一些则已经认真开始了解中国市场。 但是还有另一类硅谷投资人&#xff0c;他们认为中国的科技产…

EPI调研报告:国家的英语水平和创新能力息息相关

MinhTran:众所周知&#xff0c;阿里巴巴的马云作为全球最成功的企业家之一&#xff0c;并没有编写过一行代码&#xff0c;他本身也不是工程师出身的。事实上马云读的是英语专业&#xff0c;毕业后一开始从事的也是英语教学和翻译之类的工作&#xff0c;然后才进行创业成为企业家…