41 #include <pcl/io/io.h> 55 NODELET_ERROR (
"[onInit] Need a 'input_messages' parameter to be set before continuing!");
60 NODELET_ERROR (
"[onInit] Invalid 'input_messages' parameter given!");
89 NODELET_DEBUG (
"[input_callback] PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
90 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (),
pnh_->resolveName (
"input").c_str ());
97 NODELET_WARN (
"[input_callback] Maximum seconds limit (%f) reached. Difference is %f, erasing message in queue with stamp %f.",
maximum_seconds_,
98 (*
queue_.begin ()).first.toSec (), fabs ( ( (*
queue_.begin ()).first - cloud->header.stamp).toSec () ));
104 queue_[cloud->header.stamp].push_back (cloud);
108 std::vector<PointCloudConstPtr> &clouds =
queue_[cloud->header.stamp];
112 int data_size = cloud_out.data.size ();
113 int nr_fields = cloud_out.fields.size ();
114 int nr_points = cloud_out.width * cloud_out.height;
115 for (
size_t i = 1; i < clouds.size (); ++i)
117 assert (clouds[i]->data.size () / (clouds[i]->width * clouds[i]->height) == clouds[i]->point_step);
119 if (clouds[i]->width != cloud_out.width || clouds[i]->height != cloud_out.height)
121 NODELET_ERROR (
"[input_callback] Width/height of pointcloud %zu (%dx%d) differs from the others (%dx%d)!",
122 i, clouds[i]->width, clouds[i]->height, cloud_out.width, cloud_out.height);
126 cloud_out.point_step += clouds[i]->point_step;
128 data_size += clouds[i]->data.size ();
131 cloud_out.fields.resize (nr_fields + clouds[i]->fields.size ());
132 int delta_offset = cloud_out.fields[nr_fields - 1].offset + pcl::getFieldSize (cloud_out.fields[nr_fields - 1].datatype);
133 for (
size_t d = 0;
d < clouds[i]->fields.size (); ++
d)
135 cloud_out.fields[nr_fields +
d] = clouds[i]->fields[
d];
136 cloud_out.fields[nr_fields +
d].offset += delta_offset;
138 nr_fields += clouds[i]->fields.size ();
141 cloud_out.row_step = cloud_out.point_step * cloud_out.width;
142 cloud_out.data.resize (data_size);
145 int point_offset = 0;
146 for (
int cp = 0; cp < nr_points; ++cp)
148 for (
size_t i = 0; i < clouds.size (); ++i)
151 memcpy (&cloud_out.data[point_offset], &clouds[i]->data[cp * clouds[i]->point_step], clouds[i]->point_step);
152 point_offset += clouds[i]->point_step;
156 queue_.erase (cloud->header.stamp);
PLUGINLIB_EXPORT_CLASS(PointCloudConcatenateFieldsSynchronizer, nodelet::Nodelet)
ros::Subscriber sub_input_
The input PointCloud subscriber.
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
#define NODELET_ERROR(...)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
int maximum_queue_size_
The maximum number of messages that we can store in the queue.
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.
PointCloudConcatenateFieldsSynchronizer()
Empty constructor.
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 ...
ros::Publisher pub_output_
The output PointCloud publisher.
sensor_msgs::PointCloud2 PointCloud
PointCloud::ConstPtr PointCloudConstPtr
void input_callback(const PointCloudConstPtr &cloud)
#define NODELET_DEBUG(...)