3D激光SLAM点云地图pcd转导航可用的2D栅格地图

本文旨在帮助读者将激光点云地图转为2D栅格地图,以便完成路径规划与导航。本方法将pcd转为pgm的原理是将接收到的点云信息以"/map"话题的形式发布,用map_server来接收"/map"话题,保存2D栅格地图!

废话不多说,直接开始!

一、安装pcd2pgm

#创建工作空间
mkdir -p ~/pcd2pgm_ws/src
cd ~/pcd2pgm_ws/src
catkin_init_workspace

#克隆代码
git clone https://github.com/hujiax380/pcd2pgm.git

————————————————————————————————

需要修改pcd文件的路径以及名称

#include <ros/ros.h>
 
#include <nav_msgs/OccupancyGrid.h>
#include <nav_msgs/GetMap.h>
 
#include <sensor_msgs/PointCloud2.h>
#include <pcl/io/pcd_io.h>
#include <pcl_conversions/pcl_conversions.h>
 
#include <pcl/point_types.h>

 
std::string file_directory;
std::string file_name;
std::string pcd_file;
 
std::string map_topic_name;
 
const std::string pcd_format = ".pcd";
 
nav_msgs::OccupancyGrid map_topic_msg;

double map_resolution = 0.05;

pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_after_PassThrough(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_after_Radius(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr pcd_cloud(new pcl::PointCloud<pcl::PointXYZ>);
 
void SetMapTopicMsg(const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, nav_msgs::OccupancyGrid& msg);
 
int main(int argc, char** argv)
{
   ros::init(argc, argv, "pcl_filters");
   ros::NodeHandle nh;
   ros::NodeHandle private_nh("~");
 
   ros::Rate loop_rate(1.0);
 
   private_nh.param("file_directory", file_directory, std::string("/home/ubuntu/"));//此处需要修改为自己pcd文件的路径
   ROS_INFO("*** file_directory = %s ***\n", file_directory.c_str());
 
 
   private_nh.param("file_name", file_name, std::string("pcd_name"));//此处"pcd_name"需要修改为自己的pcd文件名,无需.pcd
   ROS_INFO("*** file_name = %s ***\n", file_name.c_str());
 
   pcd_file = file_directory + file_name + pcd_format;
   ROS_INFO("*** pcd_file = %s ***\n", pcd_file.c_str());
 
   private_nh.param("map_resolution", map_resolution, 0.05);
   private_nh.param("map_topic_name", map_topic_name, std::string("map"));
 
   ros::Publisher map_topic_pub = nh.advertise<nav_msgs::OccupancyGrid>(map_topic_name, 1);
 
   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);
   }
 
   std::cout << "输入点云点数:" << pcd_cloud->points.size() << std::endl;
 
   SetMapTopicMsg(pcd_cloud, map_topic_msg);
 
   while(ros::ok())
   {
     map_topic_pub.publish(map_topic_msg);
 
     loop_rate.sleep();
 
     ros::spinOnce();
   }
 
   return 0;
}

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; //这里是投影到xy平面,如果要投到xz/yz,这里以及后面的xy对应的数据改为你想投影的平面
 
  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;
  }
 
  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);
 
  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;
 
    msg.data[i + j * msg.info.width] = 100;

  }
}

修改之后完成编译:

cd ~/pcd2pgm_ws
catkin_make

二、转换地图

编译成功后:

roscore

#另起终端
rosrun pcd2pgm pcd2topic

终端显示pcd文件信息:

 另起终端启动map_server

#另起终端,保存地图
rosrun map_server map_saver

如此就生成可用作2D导航的yaml与pgm文件!

本文主要参考:pcd转pgm/3d点云转2d灰度图

<think>好的,我现在需要解决用户的问题:如何将HESAI XT32雷达生成的3D点云数据换为2D地图。首先,我需要理解用户的需求。HESAI XT32是一款32线激光雷达,生成的是三维点云数据,用户希望将其换为二维地图,可能用于导航或建图,比如SLAM应用。 根据用户提供的引用内容,尤其是引用[3]提到了雷达3D点云2D激光数据的方法,这可能是一个关键点。通常,将3D点云2D地图有两种主要方法:直接投影和高度切片。直接投影是将3D点云投影到水平面,比如取所有点的x和y坐标,忽略z轴,或者取z轴的平均值或特定范围。这种方法简单,但可能引入噪声。例如,地面上的点可以直接投影,而高于地面的点可能需要过滤掉,以避免障碍物误判。 另一种方法是高度切片,即选取特定高度范围内的点云。例如,只保留距离地面一定高度的点,这样可以捕捉到障碍物的边缘,适合导航。引用[3]中提到使用ROS中的`pointcloud_to_laserscan`包,这可能是常用的工具,需要配置参数如高度范围和目标帧。 接下来,用户可能需要具体的步骤。首先,配置ROS环境,安装必要的驱动和包,如HESAI雷达的ROS驱动和`pointcloud_to_laserscan`。然后,通过launch文件启动雷达,并运行换节点。在换过程中,可能需要调整参数,比如`min_height`和`max_height`来限定高度,`angle_min`和`angle_max`设置扫描角度,以及`range_max`限制最大距离。同时,需要考虑坐标系的换,确保点云数据正确映射到二维平面。 此外,用户可能需要处理地面点云,使用地面分割算法(如RANSAC或深度学习模型)来分离地面和非地面点,再投影地面点生成2D地图。建图算法如Cartographer或Hector SLAM可以处理2D激光数据生成地图。引用[1]提到Cartographer的建图流程,用户可能需要将换后的2D数据输入类似系统。 可能的问题包括点云密度过高导致处理延迟,需要降采样;动态物体干扰,需通过滤波或时间戳处理;以及坐标对齐问题,确保TF树正确配置。测试时,使用RViz可视化点云和生成的2D激光数据,调整参数直到效果满意。 总结步骤:安装依赖、启动雷达驱动、运行换节点、参数调整、地面处理(可选)、使用SLAM建图。同时,用户可能需要参考引用中的具体操作,如Cartographer的在线建图方法,将处理后的2D数据输入建图算法生成最终地图。</think>### HESAI XT32雷达3D点云2D地图方法 #### 核心步骤说明 1. **点云数据预处理** - **坐标投影**:将3D点云投影到水平面(XY平面),通常取$z$轴特定范围的点(如地面附近)。公式表示为: $$(x_i, y_i, z_i) \to (x_i, y_i) \quad \text{若} \ z_{\text{min}} \leq z_i \leq z_{\text{max}}$$ - **地面分割**:使用算法(如RANSAC)分离地面点与非地面点[^3],仅保留地面点或特定高度层的数据。 2. **3D2D工具链** - 使用ROS中的`pointcloud_to_laserscan`包,将3D点云换为2D激光扫描数据: ```xml <node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pc2laser"> <remap from="cloud_in" to="/hesai/points"/> <param name="target_frame" value="base_link"/> <param name="min_height" value="-0.5"/> <param name="max_height" value="0.5"/> </node> ``` 参数`min_height`和`max_height`控制高度切片范围。 3. **建图算法集成** - 将生成的2D激光数据输入SLAM算法(如`Cartographer`或`Hector SLAM`),通过以下配置实现地图构建: ```lua -- Cartographer配置示例 TRACKING_frame = "base_link", use_laser_scan = true, num_laser_scans = 1 ``` 支持在线建图与地图保存[^1]。 #### 参数调优建议 - **降采样**:若点云密度过高,使用`VoxelGrid`滤波器降低数据量: ```python voxel = cloud.make_voxel_grid_filter() voxel.set_leaf_size(0.1, 0.1, 0.1) # 单位:米 ``` - **动态滤波**:通过时间戳或统计滤波移除动态物体干扰。 #### 验证与可视化 - 在RViz中实时显示2D激光数据与地图: ```bash roslaunch hector_slam_launch tutorial.launch ``` 通过`Add > By Topic`添加`/scan`和`/map`话题[^2]。 ---
评论 54
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值