• attachment:example_voxelgrid_pcl_types.cpp of pcl/Tutorials/hydro

Attachment 'example_voxelgrid_pcl_types.cpp'

Download

   1 #include <ros/ros.h>
   2 // PCL specific includes
   3 #include <pcl_conversions/pcl_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 pcl::PCLPointCloud2ConstPtr& cloud)
  13 {
  14   pcl::PCLPointCloud2 cloud_filtered;
  15 
  16   // Perform the actual filtering
  17   pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
  18   sor.setInputCloud (cloud);
  19   sor.setLeafSize (0.1, 0.1, 0.1);
  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<pcl::PCLPointCloud2> ("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.
  • [get | view] (2014-07-24 05:10:30, 1.5 KB) [[attachment:example_planarsegmentation.cpp]]
  • [get | view] (2014-07-24 04:40:57, 1.3 KB) [[attachment:example_voxelgrid.cpp]]
  • [get | view] (2014-07-22 20:20:05, 0.9 KB) [[attachment:example_voxelgrid_pcl_types.cpp]]
 All files | Selected Files: delete move to page copy to page

You are not allowed to attach a file to this page.