ROS创建点云数据并在rviz中显示

本文详细介绍了如何在ROS(Kinetic)环境中从零开始创建并发布点云数据,包括工程搭建、主函数编辑、CMakeLists配置及rviz可视化展示。通过随机生成点云、构建正方体与圆柱体点云模型,深入理解点云在三维空间中的应用。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

实验环境ROS(kinetic)
1.新建工程

mkdir -p catkin_ws/src
cd catkin_ws/src
catkin_create_pkg chapter6_tutorials pcl_ros roscpp rospy sensor_msgs std_msgs 
cd ..
catkin_make 

2.编辑主函数pcl_create.cpp

#include <ros/ros.h> 
#include <pcl/point_cloud.h> 
#include <pcl_conversions/pcl_conversions.h> 
#include <sensor_msgs/PointCloud2.h> 

main (int argc, char **argv) 
{ 
	ros::init (argc, argv, "pcl_create"); 
	
	ros::NodeHandle nh; 
	ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_output", 1);     
	pcl::PointCloud<pcl::PointXYZ> cloud; 
	sensor_msgs::PointCloud2 output; 
	
	// Fill in the cloud data 
	cloud.width = 100; 
	cloud.height = 1; 
	cloud.points.resize(cloud.width * cloud.height); 
	
	for (size_t i = 0; i < cloud.points.size (); ++i)
	 { 
		 cloud.points[i].x = 1024 * rand () / (RAND_MAX + 1.0f); 
		 cloud.points[i].y = 1024 * rand () / (RAND_MAX + 1.0f); 
		 cloud.points[i].z = 1024 * rand () / (RAND_MAX + 1.0f); 
	} 
	
	//Convert the cloud to ROS message 
	pcl::toROSMsg(cloud, output); 
	output.header.frame_id = "odom"; 
	
	ros::Rate loop_rate(1); 
	while (ros::ok()) 
	{ 
		pcl_pub.publish(output);
	    ros::spinOnce(); 
		loop_rate.sleep(); 
	 } 
	return 0; 
}

3.编辑CMakeLists.txt
编辑/chapter6_tutorials/src/chapter6_tutorials路径下CMakeLists.txt加入

find_package(PCL REQUIRED) 
include_directories(include${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS}) 
add_executable(pcl_create src/pcl_create.cpp)
target_link_libraries(pcl_create ${catkin_LIBRARIES} ${PCL_LIBRARIES})

4.编译和在rviz中显示
编译

cd ~/catkin_ws | catkin_make 

刷新环境

source ~/catkin_ws/devel/setup.bash

运行

roscore
rosrun chapter6_tutorials pcl_create

打开rviz
在rviz中增加PointCloud2d
topic 选 /pcl_output
fixed Frame 输入odom
如图
在这里插入图片描述在这里插入图片描述手动创建正方体八个角点,理解点云的空间意义:
代码:

#include <ros/ros.h> 
#include <pcl/point_cloud.h> 
#include <pcl_conversions/pcl_conversions.h> 
#include <sensor_msgs/PointCloud2.h> 

main (int argc, char **argv) 
{ 
	ros::init (argc, argv, "pcl_create"); 
	
	ros::NodeHandle nh; 
	ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_output", 1);     
	pcl::PointCloud<pcl::PointXYZ> cloud; 
	sensor_msgs::PointCloud2 output; 
	
	// Fill in the cloud data 
	cloud.width = 8; 
	cloud.height = 1; //此处也可以为cloud.width = 4; cloud.height = 2; 
	cloud.points.resize(cloud.width * cloud.height); 

cloud.points[0].x = 1; 
cloud.points[0].y = 1; 
cloud.points[0].z = 0; 

cloud.points[1].x = -1; 
cloud.points[1].y = 1; 
cloud.points[1].z = 0; 

cloud.points[2].x = 1; 
cloud.points[2].y = -1; 
cloud.points[2].z = 0;
 
cloud.points[3].x = -1; 
cloud.points[3].y = -1; 
cloud.points[3].z = 0;
 
cloud.points[4].x = 1; 
cloud.points[4].y = 1; 
cloud.points[4].z = 2; 

cloud.points[5].x = -1; 
cloud.points[5].y = 1; 
cloud.points[5].z = 2; 

cloud.points[6].x = 1; 
cloud.points[6].y = -1; 
cloud.points[6].z = 2;
 
cloud.points[7].x = -1; 
cloud.points[7].y = -1; 
cloud.points[7].z = 2; 
	//Convert the cloud to ROS message 
	pcl::toROSMsg(cloud, output); 
	output.header.frame_id = "odom"; 
	
	ros::Rate loop_rate(1); 
	while (ros::ok()) 
	{ 
		pcl_pub.publish(output);
		 ros::spinOnce(); 
		 loop_rate.sleep(); 
	 } 
	return 0; 
}

在这里插入图片描述利用循环嵌套,创建一个正方体

#include <ros/ros.h> 
#include <pcl/point_cloud.h> 
#include <pcl_conversions/pcl_conversions.h> 
#include <sensor_msgs/PointCloud2.h> 

main (int argc, char **argv) 
{ 
	float table[8]={-2,-1.5,-1,-0.5,0.5,1,1.5,2};
    int point_num;
	ros::init (argc, argv, "pcl_create"); 
	
	ros::NodeHandle nh; 
	ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_output", 1);     
	pcl::PointCloud<pcl::PointXYZ> cloud; 
	sensor_msgs::PointCloud2 output; 
	
	// Fill in the cloud data 
	cloud.width = 512; 
	cloud.height = 1; 
	cloud.points.resize(cloud.width * cloud.height); 
	for(int a=0;a<8;++a)
	{
		float width = table[a];
		for(int i=0;i<8;++i)
		{
			float length = table[i];
			for(int c=0;c<8;++c)
			{
				 point_num = a*64+i*8+c;
				 cloud.points[point_num].x = width; 
				 cloud.points[point_num].y = length; 
				 cloud.points[point_num].z = table[c]; 
			}
		}	
	}

	//Convert the cloud to ROS message 
	pcl::toROSMsg(cloud, output); 
	output.header.frame_id = "odom"; 
	
	ros::Rate loop_rate(1); 
	while (ros::ok()) 
	{ 
		 pcl_pub.publish(output);
		 ros::spinOnce(); 
		 loop_rate.sleep(); 
	 } 
	return 0; 
}

在这里插入图片描述
创建一个圆柱体:

#include <ros/ros.h> 
#include <pcl/point_cloud.h> 
#include <pcl_conversions/pcl_conversions.h> 
#include <sensor_msgs/PointCloud2.h> 
#include <cmath>

#define PI 3.1415926535

main (int argc, char **argv) 
{ 
    long point_num;
	ros::init (argc, argv, "pcl_create"); 
	
	ros::NodeHandle nh; 
	ros::Publisher pcl_pub = nh.advertise<sensor_msgs::PointCloud2> ("pcl_output", 1);     
	pcl::PointCloud<pcl::PointXYZ> cloud; 
	sensor_msgs::PointCloud2 output; 
	
	// Fill in the cloud data 
	cloud.width = 360; 
	cloud.height = 21; 
	cloud.points.resize(cloud.width * cloud.height); 

	for(int z=0;z<20;++z)
	{
		for(int loop=0;loop<360;++loop)
		{
			point_num=z*360 + loop;
			float hudu = 180 *loop/PI;
			cloud.points[point_num].x = cos(hudu); 
			cloud.points[point_num].y = sin(hudu); 
			cloud.points[point_num].z = 0.3*(z+1.0f);//或者为0.3*static_cast<float>(z);目地在于int转换为float
		}	
	}
		
	//Convert the cloud to ROS message 
	pcl::toROSMsg(cloud, output); 
	output.header.frame_id = "odom"; 
	
	ros::Rate loop_rate(1); 
	while (ros::ok()) 
	{ 
		pcl_pub.publish(output);
		ros::spinOnce(); 
		loop_rate.sleep(); 
	 } 
	return 0; 
}

在这里插入图片描述

ROS(Robot Operating System)中,实时监听激光雷达点云数据利用rviz(Robot Visualization Toolkit)进行可视化,需要经过以下步骤: 1. **获取数据**: - 使用如`sensor_msgs/LaserScan`的数据包从激光雷达传感器(如Velodyne、Ouster等)读取点云数据。这通常通过`Subscriber`完成,就像之前解释过的那样。 2. **解析数据**: - 解析`LaserScan`消息,提取出包括角度、距离、反射强度等信息的点云数据。每个数据点包含了一组坐标和附加属性。 3. **将数据发布到RVIZ**: - 创建一个ROS话题或者服务(Publisher),将解析后的点云数据转换成适合rviz显示的数据结构,比如`geometry_msgs/PoseArray`或者`visualization_msgs/MarkerArray`。然后,将数据发布到`rviz`可以识别的主题(通常是`/tf`或者自定义主题)。 4. **配置rviz**: - 打开rviz创建一个新的场景或者加载预设。在rviz的“Display”选项下,添加合适的插件(例如`PointCloud2 Marker`或`Voxel Grid`)来展示点云数据。配置插件以匹配接收到的数据格式和主题。 5. **关联点云数据和机器人坐标系**: - 如果需要,你还需要确保在rviz中展示了机器人的运动状态,通常通过`TF`树来关联点云数据到车体或基座坐标系。 6. **实时更新**: - 当接收到新的点云数据时,不断地更新发布的主题,rviz会自动刷新显示。 一个简单的Python示例代码片段可能如下所示,这里仅提供关键部分: ```python # ... (其他数据处理部分) def publish_to_rviz(pointcloud_data): msg = ... # 将原始点云数据转换为适合rviz的msg格式 pub.publish(msg) # 发布数据到rviz主题 # ... (回调函数) def callback_function(data): pointcloud_data = parse_laser_scan_data(data) publish_to_rviz(pointcloud_data) # ... (启动rviz) rospy.init_node('laser_to_rviz', anonymous=True) pub = rospy.Publisher('your_topic_name', YourRvizMessageType, queue_size=10) # ... (其他部分) ```
评论 10
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值