From 32cd8f1817a23fa26b5de42b425e5150fb159bd5 Mon Sep 17 00:00:00 2001 From: ZhangWanjie Date: Fri, 26 Jul 2019 11:48:23 +0800 Subject: [PATCH] pointcloud demo --- .../src/wpb_home_pointcloud_node.cpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/wpb_home_tutorials/src/wpb_home_pointcloud_node.cpp b/wpb_home_tutorials/src/wpb_home_pointcloud_node.cpp index 5a3ed12..0d57d7c 100644 --- a/wpb_home_tutorials/src/wpb_home_pointcloud_node.cpp +++ b/wpb_home_tutorials/src/wpb_home_pointcloud_node.cpp @@ -45,12 +45,14 @@ void callbackPC(const sensor_msgs::PointCloud2ConstPtr& msg) pcl::fromROSMsg(*msg , pointCloudIn); int cloudSize = pointCloudIn.points.size(); - int pcIndex = cloudSize/2; - ROS_INFO("[pcIndex= %d] ( %.2f , %.2f , %.2f)", - pcIndex , - pointCloudIn.points[pcIndex].x, - pointCloudIn.points[pcIndex].y, - pointCloudIn.points[pcIndex].z); + for(int i=0;i