concatenate_fields.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: concatenate_fields.h 35052 2011-01-03 21:04:57Z rusu $
35  *
36  */
37 
38 #ifndef PCL_IO_CONCATENATE_FIELDS_H_
39 #define PCL_IO_CONCATENATE_FIELDS_H_
40 
41 // ROS includes
47 
48 #include <sensor_msgs/PointCloud2.h>
49 
50 namespace pcl_ros
51 {
58  {
59  public:
60  typedef sensor_msgs::PointCloud2 PointCloud;
61  typedef PointCloud::Ptr PointCloudPtr;
62  typedef PointCloud::ConstPtr PointCloudConstPtr;
63 
66 
71 
74 
75  void onInit ();
76  void subscribe ();
77  void unsubscribe ();
78  void input_callback (const PointCloudConstPtr &cloud);
79 
80  private:
83 
86 
89 
92 
95 
97  std::map<ros::Time, std::vector<PointCloudConstPtr> > queue_;
98  };
99 }
100 
101 #endif //#ifndef PCL_IO_CONCATENATE_H_
ros::Subscriber sub_input_
The input PointCloud subscriber.
int maximum_queue_size_
The maximum number of messages that we can store in the queue.
PointCloudConcatenateFieldsSynchronizer(int queue_size)
Empty constructor.
std::map< ros::Time, std::vector< PointCloudConstPtr > > queue_
A queue for messages.
double maximum_seconds_
The maximum number of seconds to wait until we drop the synchronization.
int input_messages_
The number of input messages that we expect on the input topic.
PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set ...
virtual ~PointCloudConcatenateFieldsSynchronizer()
Empty destructor.
ros::Publisher pub_output_
The output PointCloud publisher.
void input_callback(const PointCloudConstPtr &cloud)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52