40 #include "sensor_msgs/PointCloud.h"
47 #include "laser_assembler/AssembleScans.h"
48 #include "laser_assembler/AssembleScans2.h"
50 #include "boost/thread.hpp"
73 void start(
const std::string& in_topic_name);
91 virtual void ConvertToCloud(
const std::string& fixed_frame_id,
const T& scan_in, sensor_msgs::PointCloud& cloud_out) = 0 ;
114 bool buildCloud(AssembleScans::Request& req, AssembleScans::Response& resp) ;
115 bool assembleScans(AssembleScans::Request& req, AssembleScans::Response& resp) ;
116 bool buildCloud2(AssembleScans2::Request& req, AssembleScans2::Response& resp) ;
117 bool assembleScans2(AssembleScans2::Request& req, AssembleScans2::Response& resp) ;
120 std::deque<sensor_msgs::PointCloud>
scan_hist_ ;
141 double tf_cache_time_secs ;
143 if (tf_cache_time_secs < 0)
144 ROS_ERROR(
"Parameter tf_cache_time_secs<0 (%f)", tf_cache_time_secs) ;
147 ROS_INFO(
"TF Cache Time: %f Seconds", tf_cache_time_secs) ;
150 const int default_max_scans = 400 ;
153 if (tmp_max_scans < 0)
155 ROS_ERROR(
"Parameter max_scans<0 (%i)", tmp_max_scans) ;
156 tmp_max_scans = default_max_scans ;
169 int tmp_downsample_factor ;
171 if (tmp_downsample_factor < 1)
173 ROS_ERROR(
"Parameter downsample_factor<1: %i", tmp_downsample_factor) ;
174 tmp_downsample_factor = 1 ;
195 ROS_DEBUG(
"Called start(string). Starting to listen on message_filter::Subscriber the input stream");
197 ROS_ERROR(
"assembler::start() was called twice!. This is bad, and could leak memory") ;
200 scan_sub_.subscribe(n_, in_topic_name, 10);
209 ROS_DEBUG(
"Called start(). Starting tf::MessageFilter, but not initializing Subscriber");
211 ROS_ERROR(
"assembler::start() was called twice!. This is bad, and could leak memory") ;
214 scan_sub_.subscribe(n_,
"bogus", 10);
233 const T scan = *scan_ptr ;
235 sensor_msgs::PointCloud cur_cloud ;
240 ConvertToCloud(fixed_frame_, scan, cur_cloud) ;
244 ROS_WARN(
"Transform Exception %s", ex.what()) ;
249 scan_hist_mutex_.lock() ;
250 if (scan_hist_.size() == max_scans_)
252 total_pts_ -= scan_hist_.front().points.size () ;
253 scan_hist_.pop_front() ;
255 scan_hist_.push_back(cur_cloud) ;
256 total_pts_ += cur_cloud.points.size () ;
260 scan_hist_mutex_.unlock() ;
267 ROS_WARN(
"Service 'build_cloud' is deprecated. Call 'assemble_scans' instead");
268 return assembleScans(req, resp);
277 scan_hist_mutex_.lock() ;
282 while ( i < scan_hist_.size() &&
283 scan_hist_[i].header.stamp < req.begin )
287 unsigned int start_index = i ;
289 unsigned int req_pts = 0 ;
291 while ( i < scan_hist_.size() &&
292 scan_hist_[i].header.stamp < req.end )
294 req_pts += (scan_hist_[i].points.size ()+downsample_factor_-1)/downsample_factor_ ;
295 i += downsample_factor_ ;
297 unsigned int past_end_index = i ;
299 if (start_index == past_end_index)
301 resp.cloud.header.frame_id = fixed_frame_ ;
302 resp.cloud.header.stamp = req.end ;
303 resp.cloud.points.resize (0) ;
304 resp.cloud.channels.resize (0) ;
310 resp.cloud.points.resize (req_pts);
311 const unsigned int num_channels = scan_hist_[start_index].channels.size ();
312 resp.cloud.channels.resize (num_channels) ;
313 for (i = 0; i<num_channels; i++)
315 resp.cloud.channels[i].name = scan_hist_[start_index].channels[i].name ;
316 resp.cloud.channels[i].values.resize (req_pts) ;
319 resp.cloud.header.frame_id = fixed_frame_ ;
320 unsigned int cloud_count = 0 ;
321 for (i=start_index; i<past_end_index; i+=downsample_factor_)
325 for (
unsigned int chan_ind = 0; chan_ind < scan_hist_[i].channels.size(); chan_ind++)
327 if (scan_hist_[i].points.size () != scan_hist_[i].channels[chan_ind].values.size())
328 ROS_FATAL(
"Trying to add a malformed point cloud. Cloud has %u points, but channel %u has %u elems", (
int)scan_hist_[i].points.size (), chan_ind, (int)scan_hist_[i].channels[chan_ind].
values.size ());
331 for(
unsigned int j=0; j<scan_hist_[i].points.size (); j+=downsample_factor_)
333 resp.cloud.points[cloud_count].x = scan_hist_[i].points[j].x ;
334 resp.cloud.points[cloud_count].y = scan_hist_[i].points[j].y ;
335 resp.cloud.points[cloud_count].z = scan_hist_[i].points[j].z ;
337 for (
unsigned int k=0; k<num_channels; k++)
338 resp.cloud.channels[k].values[cloud_count] = scan_hist_[i].channels[k].values[j] ;
342 resp.cloud.header.stamp = scan_hist_[i].header.stamp;
345 scan_hist_mutex_.unlock() ;
347 ROS_DEBUG(
"Point Cloud Results: Aggregated from index %u->%u. BufferSize: %lu. Points in cloud: %u", start_index, past_end_index, scan_hist_.size(), (
int)resp.cloud.points.size ()) ;
354 ROS_WARN(
"Service 'build_cloud' is deprecated. Call 'assemble_scans' instead");
355 return assembleScans2(req, resp);
361 AssembleScans::Request tmp_req;
362 AssembleScans::Response tmp_res;
363 tmp_req.begin = req.begin;
364 tmp_req.end = req.end;
365 bool ret = assembleScans(tmp_req, tmp_res);