#include // PCL specific includes #include #include #include #include #include ros::Publisher pub; void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg) { // Container for original & filtered data pcl::PCLPointCloud2* cloud = new pcl::PCLPointCloud2; pcl::PCLPointCloud2ConstPtr cloudPtr(cloud); pcl::PCLPointCloud2 cloud_filtered; // Convert to PCL data type pcl_conversions::toPCL(*cloud_msg, *cloud); // Perform the actual filtering pcl::VoxelGrid sor; sor.setInputCloud (cloudPtr); sor.setLeafSize (0.1, 0.1, 0.1); sor.filter (cloud_filtered); // Convert to ROS data type sensor_msgs::PointCloud2 output; pcl_conversions::moveFromPCL(cloud_filtered, output); // Publish the data pub.publish (output); } int main (int argc, char** argv) { // Initialize ROS ros::init (argc, argv, "my_pcl_tutorial"); ros::NodeHandle nh; // Create a ROS subscriber for the input point cloud ros::Subscriber sub = nh.subscribe ("input", 1, cloud_cb); // Create a ROS publisher for the output point cloud pub = nh.advertise ("output", 1); // Spin ros::spin (); }