Attachment 'example_voxelgrid.cpp'
Download 1 #include <ros/ros.h>
2 // PCL specific includes
3 #include <pcl/ros/conversions.h>
4 #include <pcl/point_cloud.h>
5 #include <pcl/point_types.h>
6
7 #include <pcl/filters/voxel_grid.h>
8
9 ros::Publisher pub;
10
11 void
12 cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud)
13 {
14 sensor_msgs::PointCloud2 cloud_filtered;
15
16 // Perform the actual filtering
17 pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
18 sor.setInputCloud (cloud);
19 sor.setLeafSize (0.01, 0.01, 0.01);
20 sor.filter (cloud_filtered);
21
22 // Publish the data
23 pub.publish (cloud_filtered);
24 }
25
26 int
27 main (int argc, char** argv)
28 {
29 // Initialize ROS
30 ros::init (argc, argv, "my_pcl_tutorial");
31 ros::NodeHandle nh;
32
33 // Create a ROS subscriber for the input point cloud
34 ros::Subscriber sub = nh.subscribe ("input", 1, cloud_cb);
35
36 // Create a ROS publisher for the output point cloud
37 pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 1);
38
39 // Spin
40 ros::spin ();
41 }
Attached Files
To refer to attachments on a page, use attachment:filename, as shown below in the list of files. Do NOT use the URL of the [get] link, since this is subject to change and can break easily.You are not allowed to attach a file to this page.