concatenate_point_clouds.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Bosch RTC
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: transform_pointcloud.cpp 30719 2010-07-09 20:28:41Z rusu $
00035  *
00036  */
00044 // ROS core
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     // Maximum number of outgoing messages to be queued for delivery to subscribers = 1
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   // cloud_cb (!)
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 /* ]--- */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pr2_data_acquisition_tools
Author(s): Dejan Pangercic
autogenerated on Sun Oct 6 2013 11:56:39