00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2009, Willow Garage, Inc. 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: concatenate_fields.h 35052 2011-01-03 21:04:57Z rusu $ 00035 * 00036 */ 00037 00038 #ifndef PCL_IO_CONCATENATE_FIELDS_H_ 00039 #define PCL_IO_CONCATENATE_FIELDS_H_ 00040 00041 // ROS includes 00042 #include <nodelet/nodelet.h> 00043 #include <message_filters/subscriber.h> 00044 #include <message_filters/synchronizer.h> 00045 #include <message_filters/sync_policies/exact_time.h> 00046 #include <message_filters/sync_policies/approximate_time.h> 00047 00048 #include <sensor_msgs/PointCloud2.h> 00049 00050 namespace pcl_ros 00051 { 00057 class PointCloudConcatenateFieldsSynchronizer: public nodelet::Nodelet 00058 { 00059 public: 00060 typedef sensor_msgs::PointCloud2 PointCloud; 00061 typedef PointCloud::Ptr PointCloudPtr; 00062 typedef PointCloud::ConstPtr PointCloudConstPtr; 00063 00065 PointCloudConcatenateFieldsSynchronizer () : maximum_queue_size_ (3), maximum_seconds_ (0) {}; 00066 00070 PointCloudConcatenateFieldsSynchronizer (int queue_size) : maximum_queue_size_ (queue_size), maximum_seconds_ (0) {}; 00071 00073 virtual ~PointCloudConcatenateFieldsSynchronizer () {}; 00074 00075 void onInit (); 00076 void input_callback (const PointCloudConstPtr &cloud); 00077 00078 private: 00080 ros::NodeHandle private_nh_; 00081 00083 ros::Subscriber sub_input_; 00084 00086 ros::Publisher pub_output_; 00087 00089 int input_messages_; 00090 00092 int maximum_queue_size_; 00093 00095 double maximum_seconds_; 00096 00098 std::map<ros::Time, std::vector<PointCloudConstPtr> > queue_; 00099 }; 00100 } 00101 00102 #endif //#ifndef PCL_IO_CONCATENATE_H_