Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00044 
00045 #include <ros/ros.h>
00046 #include "pcl/io/pcd_io.h"
00047 #include "pcl/point_types.h"
00048 #include "pcl/filters/voxel_grid.h"
00049 
00050 using namespace std;
00051 typedef pcl::PointXYZRGB PointT;
00052 
00053 class ConcatenatePointCloudNode
00054 {
00055 protected:
00056   ros::NodeHandle nh_;
00057 public:
00058   string input_cloud_topic_;
00059   pcl::PointCloud<PointT> concatenated_pc_, concatenated_pc_filtered_;
00060   pcl::PointCloud<PointT>::ConstPtr concatenated_pc_ptr_;
00061   ros::Subscriber sub_;
00062   pcl::PCDWriter pcd_writer_;
00063   double voxel_size_;
00064   pcl::VoxelGrid<PointT> vgrid_;
00065 
00067   ConcatenatePointCloudNode  (ros::NodeHandle &n) : nh_(n)
00068   {
00069     
00070     nh_.param("input_cloud_topic", input_cloud_topic_, std::string("cloud_pcd"));
00071     nh_.param("voxel_size", voxel_size_, 0.02);
00072     sub_ = nh_.subscribe (input_cloud_topic_, 1,  &ConcatenatePointCloudNode::cloud_cb, this);
00073     ROS_INFO ("[ConcatenatePointCloudNode:] Listening for incoming data on topic %s", nh_.resolveName (input_cloud_topic_).c_str ());
00074     vgrid_.setLeafSize (voxel_size_, voxel_size_, voxel_size_);
00075     concatenated_pc_ptr_.reset(new pcl::PointCloud<PointT> ());
00076   }
00077   
00079   ~ConcatenatePointCloudNode ()
00080     {
00081       concatenated_pc_ptr_.reset(new pcl::PointCloud<PointT> (concatenated_pc_));
00082       vgrid_.setInputCloud (concatenated_pc_ptr_);
00083       vgrid_.setFilterFieldName("y");
00084       vgrid_.setFilterLimits(-3.0, 3.0);
00085       vgrid_.filter(concatenated_pc_filtered_);
00086       ROS_INFO("[ConcatenatePointCloudNode:] Writting cloud with %ld points", concatenated_pc_filtered_.points.size());
00087       pcd_writer_.write ("concatenated_cloud.pcd", concatenated_pc_filtered_, true);
00088     }
00089   
00091   
00092   void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& pc)
00093   {
00094     pcl::PointCloud<PointT> pcl_cloud;
00095     pcl::fromROSMsg(*pc, pcl_cloud);
00096     concatenated_pc_.header = pcl_cloud.header;
00097     concatenated_pc_ += pcl_cloud;
00098     ROS_INFO("[ConcatenatePointCloudNode:] concatenated cloud with %ld points", concatenated_pc_.points.size());
00099   }
00100 };
00101 
00102 int main (int argc, char** argv)
00103 {
00104   ros::init (argc, argv, "concatenate_pointcloud_node");
00105   ros::NodeHandle n("~");
00106   ConcatenatePointCloudNode cp(n);
00107   ros::spin ();
00108   return (0);
00109 }
00110 
00111