40 #include "sensor_msgs/PointCloud.h"
46 #include "laser_assembler/AssembleScans.h"
48 #include "boost/thread.hpp"
72 class BaseAssemblerSrv
102 virtual void ConvertToCloud(
const std::string& fixed_frame_id,
const T& scan_in, sensor_msgs::PointCloud& cloud_out) = 0 ;
122 bool buildCloud(AssembleScans::Request& req, AssembleScans::Response& resp) ;
126 std::deque<sensor_msgs::PointCloud>
scan_hist_ ;
150 double tf_cache_time_secs ;
152 if (tf_cache_time_secs < 0)
153 ROS_ERROR(
"Parameter tf_cache_time_secs<0 (%f)", tf_cache_time_secs) ;
156 ROS_INFO(
"TF Cache Time: %f Seconds", tf_cache_time_secs) ;
159 const int default_max_scans = 400 ;
162 if (tmp_max_scans < 0)
164 ROS_ERROR(
"Parameter max_scans<0 (%i)", tmp_max_scans) ;
165 tmp_max_scans = default_max_scans ;
175 ROS_ERROR(
"Need to set parameter fixed_frame") ;
178 int tmp_downsample_factor ;
180 if (tmp_downsample_factor < 1)
182 ROS_ERROR(
"Parameter downsample_factor<1: %i", tmp_downsample_factor) ;
183 tmp_downsample_factor = 1 ;
206 ROS_INFO(
"Starting to listen on the input stream") ;
208 ROS_ERROR(
"assembler::start() was called twice!. This is bad, and could leak memory") ;
211 scan_sub_.subscribe(n_,
"scan_in", 10);
230 const T scan = *scan_ptr ;
232 sensor_msgs::PointCloud cur_cloud ;
237 ConvertToCloud(fixed_frame_, scan, cur_cloud) ;
241 ROS_WARN(
"Transform Exception %s", ex.what()) ;
246 scan_hist_mutex_.lock() ;
247 if (scan_hist_.size() == max_scans_)
249 total_pts_ -= scan_hist_.front().points.size() ;
250 scan_hist_.pop_front() ;
252 scan_hist_.push_back(cur_cloud) ;
253 total_pts_ += cur_cloud.points.size() ;
257 scan_hist_mutex_.unlock() ;
265 scan_hist_mutex_.lock() ;
270 while ( i < scan_hist_.size() &&
271 scan_hist_[i].header.stamp < req.begin )
275 unsigned int start_index = i ;
277 unsigned int req_pts = 0 ;
279 while ( i < scan_hist_.size() &&
280 scan_hist_[i].header.stamp < req.end )
282 req_pts += (scan_hist_[i].points.size()+downsample_factor_-1)/downsample_factor_ ;
283 i += downsample_factor_ ;
285 unsigned int past_end_index = i ;
287 if (start_index == past_end_index)
289 resp.cloud.header.frame_id = fixed_frame_ ;
290 resp.cloud.header.stamp = req.end ;
291 resp.cloud.points.resize(0) ;
292 resp.cloud.channels.resize(0) ;
298 resp.cloud.points.resize( req_pts ) ;
299 const unsigned int num_channels = scan_hist_[start_index].channels.size() ;
300 resp.cloud.channels.resize(num_channels) ;
301 for (i = 0; i<num_channels; i++)
303 resp.cloud.channels[i].name = scan_hist_[start_index].channels[i].name ;
304 resp.cloud.channels[i].values.resize(req_pts) ;
307 resp.cloud.header.frame_id = fixed_frame_ ;
308 unsigned int cloud_count = 0 ;
309 for (i=start_index; i<past_end_index; i+=downsample_factor_)
311 for(
unsigned int j=0; j<scan_hist_[i].points.size(); j+=downsample_factor_)
313 resp.cloud.points[cloud_count].x = scan_hist_[i].points[j].x ;
314 resp.cloud.points[cloud_count].y = scan_hist_[i].points[j].y ;
315 resp.cloud.points[cloud_count].z = scan_hist_[i].points[j].z ;
316 for (
unsigned int k=0; k<num_channels; k++)
317 resp.cloud.channels[k].values[cloud_count] = scan_hist_[i].channels[k].values[j] ;
321 resp.cloud.header.stamp = scan_hist_[i].header.stamp;
324 scan_hist_mutex_.unlock() ;
326 ROS_DEBUG(
"Point Cloud Results: Aggregated from index %u->%u. BufferSize: %lu. Points in cloud: %lu", start_index, past_end_index, scan_hist_.size(), resp.cloud.points.size()) ;