concatenate_data.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_data.h 35231 2011-01-14 05:33:20Z rusu $
35  *
36  */
37 
38 #ifndef PCL_IO_CONCATENATE_DATA_H_
39 #define PCL_IO_CONCATENATE_DATA_H_
40 
41 // ROS includes
42 #include <tf/transform_listener.h>
49 
50 namespace pcl_ros
51 {
53 
61  {
62  public:
63  typedef sensor_msgs::PointCloud2 PointCloud2;
64  typedef PointCloud2::Ptr PointCloud2Ptr;
65  typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
66 
69 
74 
77 
78  void onInit ();
79  void subscribe ();
80  void unsubscribe ();
81 
82  private:
85 
88 
91 
93  std::vector<boost::shared_ptr<message_filters::Subscriber<PointCloud2> > > filters_;
94 
96  std::string output_frame_;
97 
100 
103 
107 
113 
118  inline void
119  input_callback (const PointCloud2ConstPtr &input)
120  {
121  PointCloud2 cloud;
122  cloud.header.stamp = input->header.stamp;
123  nf_.add (boost::make_shared<PointCloud2> (cloud));
124  }
125 
127  void input (const PointCloud2::ConstPtr &in1, const PointCloud2::ConstPtr &in2,
128  const PointCloud2::ConstPtr &in3, const PointCloud2::ConstPtr &in4,
129  const PointCloud2::ConstPtr &in5, const PointCloud2::ConstPtr &in6,
130  const PointCloud2::ConstPtr &in7, const PointCloud2::ConstPtr &in8);
131 
132  void combineClouds (const PointCloud2 &in1, const PointCloud2 &in2, PointCloud2 &out);
133  };
134 }
135 
136 #endif //#ifndef PCL_ROS_IO_CONCATENATE_H_
XmlRpc::XmlRpcValue input_topics_
Input point cloud topics.
PointCloudConcatenateDataSynchronizer(int queue_size)
Empty constructor.
int maximum_queue_size_
The maximum number of messages that we can store in the queue.
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
std::string output_frame_
Output TF frame the concatenated points should be transformed to.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > ts_a_
Synchronizer.
message_filters::PassThrough< PointCloud2 > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set ...
void input(const PointCloud2::ConstPtr &in1, const PointCloud2::ConstPtr &in2, const PointCloud2::ConstPtr &in3, const PointCloud2::ConstPtr &in4, const PointCloud2::ConstPtr &in5, const PointCloud2::ConstPtr &in6, const PointCloud2::ConstPtr &in7, const PointCloud2::ConstPtr &in8)
Input callback for 8 synchronized topics.
ros::Publisher pub_output_
The output PointCloud publisher.
void combineClouds(const PointCloud2 &in1, const PointCloud2 &in2, PointCloud2 &out)
virtual ~PointCloudConcatenateDataSynchronizer()
Empty destructor.
std::vector< boost::shared_ptr< message_filters::Subscriber< PointCloud2 > > > filters_
A vector of message filters.
void add(const MConstPtr &msg)
tf::TransformListener tf_
TF listener object.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2, PointCloud2 > > > ts_e_
void input_callback(const PointCloud2ConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18