Go to the documentation of this file.00001
00002 #include "pcl/io/pcd_io.h"
00003 #include "pcl/point_types.h"
00004
00005 #include "pcl/filters/voxel_grid.h"
00006
00007 int main (int argc, char** argv)
00008 {
00009 sensor_msgs::PointCloud2 cloud, cloud_filtered;
00010
00011
00012 pcl::PCDReader reader;
00013 reader.read ("table_scene_lms400.pcd", cloud);
00014
00015 ROS_INFO ("PointCloud before filtering: %d data points (%s).", cloud.width * cloud.height, pcl::getFieldsList (cloud).c_str ());
00016
00017
00018 pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
00019 sor.setInputCloud (boost::make_shared<sensor_msgs::PointCloud2> (cloud));
00020 sor.setLeafSize (0.01, 0.01, 0.01);
00021 sor.filter (cloud_filtered);
00022
00023 ROS_INFO ("PointCloud after filtering: %d data points (%s).", cloud_filtered.width * cloud_filtered.height, pcl::getFieldsList (cloud_filtered).c_str ());
00024
00025 pcl::PCDWriter writer;
00026 writer.write ("table_scene_lms400_downsampled.pcd", cloud_filtered, false);
00027
00028 return (0);
00029 }
00030
00031