mirror of
https://github.com/6-robot/wpb_home.git
synced 2025-09-15 12:58:59 +08:00
pointcloud demo
This commit is contained in:
parent
f6ec90651d
commit
32cd8f1817
@ -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<cloudSize;i++)
|
||||
{
|
||||
ROS_INFO("[i= %d] ( %.2f , %.2f , %.2f)",
|
||||
i ,
|
||||
pointCloudIn.points[i].x,
|
||||
pointCloudIn.points[i].y,
|
||||
pointCloudIn.points[i].z);
|
||||
}
|
||||
}
|
||||
|
||||
int main(int argc, char **argv)
|
||||
|
||||
Loading…
Reference in New Issue
Block a user