concatenate_fields.cpp
Go to the documentation of this file.
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.cpp 35052 2011-01-03 21:04:57Z rusu $
00035  *
00036  */
00037 
00040 #include <pluginlib/class_list_macros.h>
00041 #include <pcl/io/io.h>
00042 #include "pcl_ros/io/concatenate_fields.h"
00043 
00045 void
00046 pcl_ros::PointCloudConcatenateFieldsSynchronizer::onInit ()
00047 {
00048   private_nh_ = getMTPrivateNodeHandle ();
00049   // ---[ Mandatory parameters
00050   if (!private_nh_.getParam ("input_messages", input_messages_))
00051   {
00052     NODELET_ERROR ("[onInit] Need a 'input_messages' parameter to be set before continuing!");
00053     return;
00054   }
00055   if (input_messages_ < 2)
00056   {
00057     NODELET_ERROR ("[onInit] Invalid 'input_messages' parameter given!");
00058     return;
00059   }
00060   // ---[ Optional parameters
00061   private_nh_.getParam ("max_queue_size", maximum_queue_size_);
00062   private_nh_.getParam ("maximum_seconds", maximum_seconds_);
00063   sub_input_ = private_nh_.subscribe ("input", maximum_queue_size_,  &PointCloudConcatenateFieldsSynchronizer::input_callback, this);
00064   pub_output_ = private_nh_.advertise<sensor_msgs::PointCloud2> ("output", maximum_queue_size_);
00065 }
00066 
00068 void
00069 pcl_ros::PointCloudConcatenateFieldsSynchronizer::input_callback (const PointCloudConstPtr &cloud)
00070 {
00071   NODELET_DEBUG ("[input_callback] PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
00072                  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), private_nh_.resolveName ("input").c_str ());
00073 
00074   // Erase old data in the queue
00075   if (maximum_seconds_ > 0 && queue_.size () > 0)
00076   {
00077     while (fabs ( ( (*queue_.begin ()).first - cloud->header.stamp).toSec () ) > maximum_seconds_ && queue_.size () > 0)
00078     {
00079       NODELET_WARN ("[input_callback] Maximum seconds limit (%f) reached. Difference is %f, erasing message in queue with stamp %f.", maximum_seconds_,
00080                  (*queue_.begin ()).first.toSec (), fabs ( ( (*queue_.begin ()).first - cloud->header.stamp).toSec () ));
00081       queue_.erase (queue_.begin ());
00082     }
00083   }
00084 
00085   // Push back new data
00086   queue_[cloud->header.stamp].push_back (cloud);
00087   if ((int)queue_[cloud->header.stamp].size () >= input_messages_)
00088   {
00089     // Concatenate together and publish
00090     std::vector<PointCloudConstPtr> &clouds = queue_[cloud->header.stamp];
00091     PointCloud cloud_out = *clouds[0];
00092 
00093     // Resize the output dataset
00094     int data_size = cloud_out.data.size ();
00095     int nr_fields = cloud_out.fields.size ();
00096     int nr_points = cloud_out.width * cloud_out.height;
00097     for (size_t i = 1; i < clouds.size (); ++i)
00098     {
00099       assert (clouds[i]->data.size () / (clouds[i]->width * clouds[i]->height) == clouds[i]->point_step);
00100 
00101       if (clouds[i]->width != cloud_out.width || clouds[i]->height != cloud_out.height)
00102       {
00103         NODELET_ERROR ("[input_callback] Width/height of pointcloud %zu (%dx%d) differs from the others (%dx%d)!", 
00104             i, clouds[i]->width, clouds[i]->height, cloud_out.width, cloud_out.height);
00105         break;
00106       }
00107       // Point step must increase with the length of each new field
00108       cloud_out.point_step += clouds[i]->point_step;
00109       // Resize data to hold all clouds
00110       data_size += clouds[i]->data.size ();
00111 
00112       // Concatenate fields
00113       cloud_out.fields.resize (nr_fields + clouds[i]->fields.size ());
00114       int delta_offset = cloud_out.fields[nr_fields - 1].offset + pcl::getFieldSize (cloud_out.fields[nr_fields - 1].datatype);
00115       for (size_t d = 0; d < clouds[i]->fields.size (); ++d)
00116       {
00117         cloud_out.fields[nr_fields + d] = clouds[i]->fields[d];
00118         cloud_out.fields[nr_fields + d].offset += delta_offset;
00119       }
00120       nr_fields += clouds[i]->fields.size ();
00121     }
00122     // Recalculate row_step
00123     cloud_out.row_step = cloud_out.point_step * cloud_out.width;
00124     cloud_out.data.resize (data_size);
00125 
00126     // Iterate over each point and perform the appropriate memcpys
00127     int point_offset = 0;
00128     for (int cp = 0; cp < nr_points; ++cp)
00129     {
00130       for (size_t i = 0; i < clouds.size (); ++i)
00131       {
00132         // Copy each individual point
00133         memcpy (&cloud_out.data[point_offset], &clouds[i]->data[cp * clouds[i]->point_step], clouds[i]->point_step);
00134         point_offset += clouds[i]->point_step;
00135       }
00136     }
00137     pub_output_.publish (boost::make_shared<const PointCloud> (cloud_out));
00138     queue_.erase (cloud->header.stamp);
00139   }
00140 
00141   // Clean the queue to avoid overflowing
00142   if (maximum_queue_size_ > 0)
00143   {
00144     while ((int)queue_.size () > maximum_queue_size_)
00145       queue_.erase (queue_.begin ());
00146   }
00147 
00148 }
00149 
00150 typedef pcl_ros::PointCloudConcatenateFieldsSynchronizer PointCloudConcatenateFieldsSynchronizer;
00151 PLUGINLIB_DECLARE_CLASS (pcl, PointCloudConcatenateFieldsSynchronizer, PointCloudConcatenateFieldsSynchronizer, nodelet::Nodelet);
00152 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Tue Mar 5 2013 13:54:40