concatenate_fields.cpp
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.cpp 35052 2011-01-03 21:04:57Z rusu $
35  *
36  */
37 
42 
44 
46 void
48 {
50 
51  // ---[ Mandatory parameters
52  if (!pnh_->getParam ("input_messages", input_messages_))
53  {
54  NODELET_ERROR ("[onInit] Need a 'input_messages' parameter to be set before continuing!");
55  return;
56  }
57  if (input_messages_ < 2)
58  {
59  NODELET_ERROR ("[onInit] Invalid 'input_messages' parameter given!");
60  return;
61  }
62  // ---[ Optional parameters
63  pnh_->getParam ("max_queue_size", maximum_queue_size_);
64  pnh_->getParam ("maximum_seconds", maximum_seconds_);
65  pub_output_ = advertise<sensor_msgs::PointCloud2> (*pnh_, "output", maximum_queue_size_);
66 
68 }
69 
71 void
73 {
74  sub_input_ = pnh_->subscribe ("input", maximum_queue_size_, &PointCloudConcatenateFieldsSynchronizer::input_callback, this);
75 }
76 
78 void
80 {
81  sub_input_.shutdown ();
82 }
83 
85 void
87 {
88  NODELET_DEBUG ("[input_callback] PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
89  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ());
90 
91  // Erase old data in the queue
92  if (maximum_seconds_ > 0 && queue_.size () > 0)
93  {
94  while (fabs ( ( (*queue_.begin ()).first - cloud->header.stamp).toSec () ) > maximum_seconds_ && queue_.size () > 0)
95  {
96  NODELET_WARN ("[input_callback] Maximum seconds limit (%f) reached. Difference is %f, erasing message in queue with stamp %f.", maximum_seconds_,
97  (*queue_.begin ()).first.toSec (), fabs ( ( (*queue_.begin ()).first - cloud->header.stamp).toSec () ));
98  queue_.erase (queue_.begin ());
99  }
100  }
101 
102  // Push back new data
103  queue_[cloud->header.stamp].push_back (cloud);
104  if ((int)queue_[cloud->header.stamp].size () >= input_messages_)
105  {
106  // Concatenate together and publish
107  std::vector<PointCloudConstPtr> &clouds = queue_[cloud->header.stamp];
108  PointCloud cloud_out = *clouds[0];
109 
110  // Resize the output dataset
111  size_t data_size = cloud_out.data.size ();
112  size_t nr_fields = cloud_out.fields.size ();
113  size_t nr_points = cloud_out.width * cloud_out.height;
114  for (size_t i = 1; i < clouds.size (); ++i)
115  {
116  assert (clouds[i]->data.size () / (clouds[i]->width * clouds[i]->height) == clouds[i]->point_step);
117 
118  if (clouds[i]->width != cloud_out.width || clouds[i]->height != cloud_out.height)
119  {
120  NODELET_ERROR ("[input_callback] Width/height of pointcloud %zu (%dx%d) differs from the others (%dx%d)!",
121  i, clouds[i]->width, clouds[i]->height, cloud_out.width, cloud_out.height);
122  break;
123  }
124  // Point step must increase with the length of each new field
125  cloud_out.point_step += clouds[i]->point_step;
126  // Resize data to hold all clouds
127  data_size += clouds[i]->data.size ();
128 
129  // Concatenate fields
130  cloud_out.fields.resize (nr_fields + clouds[i]->fields.size ());
131  int delta_offset = cloud_out.fields[nr_fields - 1].offset + pcl::getFieldSize (cloud_out.fields[nr_fields - 1].datatype);
132  for (size_t d = 0; d < clouds[i]->fields.size (); ++d)
133  {
134  cloud_out.fields[nr_fields + d] = clouds[i]->fields[d];
135  cloud_out.fields[nr_fields + d].offset += delta_offset;
136  }
137  nr_fields += clouds[i]->fields.size ();
138  }
139  // Recalculate row_step
140  cloud_out.row_step = cloud_out.point_step * cloud_out.width;
141  cloud_out.data.resize (data_size);
142 
143  // Iterate over each point and perform the appropriate memcpys
144  int point_offset = 0;
145  for (size_t cp = 0; cp < nr_points; ++cp)
146  {
147  for (size_t i = 0; i < clouds.size (); ++i)
148  {
149  // Copy each individual point
150  memcpy (&cloud_out.data[point_offset], &clouds[i]->data[cp * clouds[i]->point_step], clouds[i]->point_step);
151  point_offset += clouds[i]->point_step;
152  }
153  }
154  pub_output_.publish (boost::make_shared<const PointCloud> (cloud_out));
155  queue_.erase (cloud->header.stamp);
156  }
157 
158  // Clean the queue to avoid overflowing
159  if (maximum_queue_size_ > 0)
160  {
161  while ((int)queue_.size () > maximum_queue_size_)
162  queue_.erase (queue_.begin ());
163  }
164 
165 }
166 
169 
pcl_ros::PointCloudConcatenateFieldsSynchronizer::onInit
void onInit()
Definition: concatenate_fields.cpp:47
NODELET_ERROR
#define NODELET_ERROR(...)
nodelet_topic_tools::NodeletLazy::pnh_
boost::shared_ptr< ros::NodeHandle > pnh_
pcl::getFieldsList
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloud
sensor_msgs::PointCloud2 PointCloud
Definition: concatenate_fields.h:56
NODELET_WARN
#define NODELET_WARN(...)
pcl_ros::PointCloudConcatenateFieldsSynchronizer::input_callback
void input_callback(const PointCloudConstPtr &cloud)
Definition: concatenate_fields.cpp:86
pcl_ros::PointCloudConcatenateFieldsSynchronizer::input_messages_
int input_messages_
The number of input messages that we expect on the input topic.
Definition: concatenate_fields.h:84
pcl_ros::PointCloudConcatenateFieldsSynchronizer::PointCloudConstPtr
PointCloud::ConstPtr PointCloudConstPtr
Definition: concatenate_fields.h:58
pcl_ros::PointCloudConcatenateFieldsSynchronizer::pub_output_
ros::Publisher pub_output_
The output PointCloud publisher.
Definition: concatenate_fields.h:81
pcl_ros::PointCloudConcatenateFieldsSynchronizer::subscribe
void subscribe()
Definition: concatenate_fields.cpp:72
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
pcl_ros::PointCloudConcatenateFieldsSynchronizer::maximum_seconds_
double maximum_seconds_
The maximum number of seconds to wait until we drop the synchronization.
Definition: concatenate_fields.h:90
nodelet_topic_tools::NodeletLazy::onInit
virtual void onInit()
pcl_ros::PointCloudConcatenateFieldsSynchronizer::maximum_queue_size_
int maximum_queue_size_
The maximum number of messages that we can store in the queue.
Definition: concatenate_fields.h:87
d
d
pcl_ros::PointCloudConcatenateFieldsSynchronizer
PointCloudConcatenateFieldsSynchronizer is a special form of data synchronizer: it listens for a set ...
Definition: concatenate_fields.h:53
pcl_ros::PointCloudConcatenateFieldsSynchronizer::unsubscribe
void unsubscribe()
Definition: concatenate_fields.cpp:79
nodelet::Nodelet
nodelet_topic_tools::NodeletLazy::onInitPostProcess
virtual void onInitPostProcess()
concatenate_fields.h
class_list_macros.hpp
PointCloudConcatenateFieldsSynchronizer
pcl_ros::PointCloudConcatenateFieldsSynchronizer PointCloudConcatenateFieldsSynchronizer
Definition: concatenate_fields.cpp:167
NODELET_DEBUG
#define NODELET_DEBUG(...)
pcl_conversions.h


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40