Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
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
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
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
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
00086 queue_[cloud->header.stamp].push_back (cloud);
00087 if ((int)queue_[cloud->header.stamp].size () >= input_messages_)
00088 {
00089
00090 std::vector<PointCloudConstPtr> &clouds = queue_[cloud->header.stamp];
00091 PointCloud cloud_out = *clouds[0];
00092
00093
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
00108 cloud_out.point_step += clouds[i]->point_step;
00109
00110 data_size += clouds[i]->data.size ();
00111
00112
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
00123 cloud_out.row_step = cloud_out.point_step * cloud_out.width;
00124 cloud_out.data.resize (data_size);
00125
00126
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
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
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