功能包创建
cd Downloads/ROS
mkdir -p pcdreadshow_ws/src
cd src
catkin_init_workspace
catkin_create_pkg read_pcd pcl_conversions pcl_ros roscpp sensor_msgs
读取点云文件并发布
#include<ros/ros.h>
#include<pcl/point_cloud.h>
#include<pcl_conversions/pcl_conversions.h>
#include<sensor_msgs/PointCloud2.h>
#include<pcl/io/pcd_io.h>
int main(int argc,char **argv){
ros::init(argc,argv,"pcd_pub");
ros::NodeHandle nh;
ros::Publisher pcl_pub=nh.advertise<sensor_msgs::PointCloud2> ("pcl_output",1);
pcl::PointCloud<pcl::PointXYZ> cloud;
sensor_msgs::PointCloud2 output;
std::string file_path;
nh.param<std::string>("file_path", file_path, "/home/wyh/Downloads/ROS/pcdreadshow_ws/src/read_pcd/src/data/pcd/data_1/0000000001.pcd")
pcl::io::loadPCDFile(file_path,cloud);//通过launch文件修改路径即可
pcl::toROSMsg(cloud,output);
output.header.frame_id="map";
ros::Rate loop_rate(1);
while (ros::ok())
{
pcl_pub.publish(output);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
launch文件
<launch>
<param name="file_path" value="/home/wyh/Downloads/ROS/pcdreadshow_ws/src/read_pcd/src/data/pcd/data_1/0000000001.pcd">
<node type="read_pcd" value="read_pcd" pkg="read_pcd">
</node>
</launch>
编译CmakeLists.txt
add_executable(read_pcd src/read_pcd.cpp)
target_link_libraries(read_pcd ${catkin_LIBRARIES})
即可实现pcd文件的点云可视化。
这个是点云到栅格地图之后的效果
点云转栅格地图,最近为了将点云地图用于导航,所以找了一个点云转栅格的内容:
参考内容:https://blog.csdn.net/Draonly/article/details/124537069
在使用导航时,通常会根据二维栅格地图做路径规划,需要将三维点云地图转化成栅格地图。
其实主要使用了主要步骤包括
- 对输入点云进行直通滤波,获取限定高度范围的数据
- 在进行半径滤波,去除部分孤立点
- 转换为栅格地图
github链接:https://link.csdn.net/?target=https%3A%2F%2Fgithub.com%2FHinson-A%2Fpcd2pgm_package
<!-- -->
<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>