最近在学习PointCloud,于是想尝试着自己创建一个动态的彩色点云。
在网上找了一些,但都不是动态的,于是经过自己修改,做了一个项目。
主要思想:把点云点的赋值过程都放入while循环中,设置好频率,这样每次发送出来的都是不一样的赋值之后的点云数据,就是动态的了。详细注释请看代码。
主程序pcl_pub.cpp代码:
#include <iostream>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "color"); //初始化了一个节点,名字为color
ros::NodeHandle n;
ros::Publisher pub = n.advertise<sensor_msgs::PointCloud2>("/color_cloud", 1000); //建立了一个发布器,主题是color_cloud,方便之后发布点云
ros::Rate rate(2); //点云更新频率2Hz
unsigned int num_points = 100; //点云大小为100
pcl::PointCloud<pcl::PointXYZRGB> cloud; //建立了一个pcl的点云(不能直接发布)
cloud.points.resize(num_points); //点云初始化
sensor_msgs::PointCloud2 output_msg; //建立一个可以直接发布的点云
while (ros::ok()) {
output_msg.header.stamp = ros::Time::now();
for (int i = 0; i < num_points; i++) {
//点云中每个点位于一个10*10*10的方块内随机分布,颜色也随机
cloud.points[i].x = 10 * rand () / (RAND_MAX + 1.0f); // rand () / (RAND_MAX + 1.0f)为[0.1) rand () / (RAND_MAX )为[0.1]
cloud.points[i].y = 10 * rand () / (RAND_MAX + 1.0f);
cloud.points[i].z = 10 * rand () / (RAND_MAX + 1.0f);
cloud.points[i].r = (rand() % (255+1)); //(rand() % (b-a+1))+ a
cloud.points[i].g = (rand() % (255+1));
cloud.points[i].b = (rand() % (255+1));
}
pcl::toROSMsg(cloud, output_msg); //将点云转化为消息才能发布
output_msg.header.frame_id = "map"; //frame_id为map,rviz中就不用改了
pub.publish(output_msg); //发布出去
rate.sleep();
}
ros::spin();
return 0;
}
CMakeLists.txt文件内容为
cmake_minimum_required(VERSION 2.6 FATAL_ERROR)
project(pcl_pub)
set(PACKAGE_DEPENDENCIES
roscpp
sensor_msgs
pcl_ros
pcl_conversions
std_srvs
message_generation
std_msgs
)
find_package(PCL 1.3 REQUIRED COMPONENTS common io)
find_package(catkin REQUIRED COMPONENTS ${PACKAGE_DEPENDENCIES})
include_directories(${catkin_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
add_executable(pcl_pub pcl_pub.cpp)
target_link_libraries(pcl_pub ${PCL_LIBRARIES} ${catkin_LIBRARIES} )
按照正常的步骤编译即可。
最后运行./pcl_pub,打开rviz可以查看效果,如下