3434
3535// ! \author Vijay Pradeep
3636
37+ #ifndef LASER_ASSEMBLER_BASE_ASSEMBLER_H
38+ #define LASER_ASSEMBLER_BASE_ASSEMBLER_H
39+
3740#include " ros/ros.h"
3841#include " tf/transform_listener.h"
3942#include " tf/message_filter.h"
40- #include " sensor_msgs/PointCloud.h"
4143#include " sensor_msgs/point_cloud_conversion.h"
4244#include " message_filters/subscriber.h"
4345
@@ -56,7 +58,7 @@ namespace laser_assembler
5658/* *
5759 * \brief Maintains a history of point clouds and generates an aggregate point cloud upon request
5860 */
59- template <class T >
61+ template <class T , class V >
6062class BaseAssembler
6163{
6264public:
@@ -88,7 +90,7 @@ class BaseAssembler
8890 * \param scan_in The scan that we want to convert
8991 * \param cloud_out The result of transforming scan_in into a cloud in frame fixed_frame_id
9092 */
91- virtual void ConvertToCloud (const std::string& fixed_frame_id, const T& scan_in, sensor_msgs::PointCloud & cloud_out) = 0 ;
93+ virtual void Convert (const std::string& fixed_frame_id, const T& scan_in, V & cloud_out) = 0 ;
9294
9395protected:
9496 tf::TransformListener* tf_ ;
@@ -97,45 +99,32 @@ class BaseAssembler
9799 ros::NodeHandle private_ns_;
98100 ros::NodeHandle n_;
99101
102+ // ! \brief Stores history of scans
103+ std::deque<V> scan_hist_ ;
104+ boost::mutex scan_hist_mutex_ ;
105+
106+ // ! \brief The frame to transform data into upon receipt
107+ std::string fixed_frame_ ;
108+
109+ // ! \brief Specify how much to downsample the data. A value of 1 preserves all the data. 3 would keep 1/3 of the data.
110+ unsigned int downsample_factor_ ;
111+
100112private:
101113 // ROS Input/Ouptut Handling
102- ros::ServiceServer build_cloud_server_;
103- ros::ServiceServer assemble_scans_server_;
104- ros::ServiceServer build_cloud_server2_;
105- ros::ServiceServer assemble_scans_server2_;
106114 message_filters::Subscriber<T> scan_sub_;
107115 message_filters::Connection tf_filter_connection_;
108116
109117 // ! \brief Callback function for every time we receive a new scan
110118 // void scansCallback(const tf::MessageNotifier<T>::MessagePtr& scan_ptr, const T& testA)
111119 virtual void msgCallback (const boost::shared_ptr<const T>& scan_ptr) ;
112120
113- // ! \brief Service Callback function called whenever we need to build a cloud
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) ;
118-
119- // ! \brief Stores history of scans
120- std::deque<sensor_msgs::PointCloud> scan_hist_ ;
121- boost::mutex scan_hist_mutex_ ;
122-
123- // ! \brief The number points currently in the scan history
124- unsigned int total_pts_ ;
125-
126121 // ! \brief The max number of scans to store in the scan history
127122 unsigned int max_scans_ ;
128123
129- // ! \brief The frame to transform data into upon receipt
130- std::string fixed_frame_ ;
131-
132- // ! \brief Specify how much to downsample the data. A value of 1 preserves all the data. 3 would keep 1/3 of the data.
133- unsigned int downsample_factor_ ;
134-
135124} ;
136125
137- template <class T >
138- BaseAssembler<T>::BaseAssembler(const std::string& max_size_param_name) : private_ns_(" ~" )
126+ template <class T , class V >
127+ BaseAssembler<T, V >::BaseAssembler(const std::string& max_size_param_name) : private_ns_(" ~" )
139128{
140129 // **** Initialize TransformListener ****
141130 double tf_cache_time_secs ;
@@ -157,7 +146,6 @@ BaseAssembler<T>::BaseAssembler(const std::string& max_size_param_name) : privat
157146 }
158147 max_scans_ = tmp_max_scans ;
159148 ROS_INFO (" Max Scans in History: %u" , max_scans_) ;
160- total_pts_ = 0 ; // We're always going to start with no points in our history
161149
162150 // ***** Set fixed_frame *****
163151 private_ns_.param (" fixed_frame" , fixed_frame_, std::string (" ERROR_NO_NAME" ));
@@ -176,21 +164,14 @@ BaseAssembler<T>::BaseAssembler(const std::string& max_size_param_name) : privat
176164 downsample_factor_ = tmp_downsample_factor ;
177165 if (downsample_factor_ != 1 )
178166 ROS_WARN (" Downsample set to [%u]. Note that this is an unreleased/unstable feature" , downsample_factor_);
179-
180- // ***** Start Services *****
181- build_cloud_server_ = n_.advertiseService (" build_cloud" , &BaseAssembler<T>::buildCloud, this );
182- assemble_scans_server_ = n_.advertiseService (" assemble_scans" , &BaseAssembler<T>::assembleScans, this );
183- build_cloud_server2_ = n_.advertiseService (" build_cloud2" , &BaseAssembler<T>::buildCloud2, this );
184- assemble_scans_server2_ = n_.advertiseService (" assemble_scans2" , &BaseAssembler<T>::assembleScans2, this );
185-
186167 // ***** Start Listening to Data *****
187168 // (Well, don't start listening just yet. Keep this as null until we actually start listening, when start() is called)
188169 tf_filter_ = NULL ;
189170
190171}
191172
192- template <class T >
193- void BaseAssembler<T>::start(const std::string& in_topic_name)
173+ template <class T , class V >
174+ void BaseAssembler<T, V >::start(const std::string& in_topic_name)
194175{
195176 ROS_DEBUG (" Called start(string). Starting to listen on message_filter::Subscriber the input stream" );
196177 if (tf_filter_)
@@ -199,12 +180,12 @@ void BaseAssembler<T>::start(const std::string& in_topic_name)
199180 {
200181 scan_sub_.subscribe (n_, in_topic_name, 10 );
201182 tf_filter_ = new tf::MessageFilter<T>(scan_sub_, *tf_, fixed_frame_, 10 );
202- tf_filter_->registerCallback ( boost::bind (&BaseAssembler<T>::msgCallback, this , _1) );
183+ tf_filter_->registerCallback ( boost::bind (&BaseAssembler<T, V >::msgCallback, this , _1) );
203184 }
204185}
205186
206- template <class T >
207- void BaseAssembler<T>::start()
187+ template <class T , class V >
188+ void BaseAssembler<T, V >::start()
208189{
209190 ROS_DEBUG (" Called start(). Starting tf::MessageFilter, but not initializing Subscriber" );
210191 if (tf_filter_)
@@ -213,31 +194,31 @@ void BaseAssembler<T>::start()
213194 {
214195 scan_sub_.subscribe (n_, " bogus" , 10 );
215196 tf_filter_ = new tf::MessageFilter<T>(scan_sub_, *tf_, fixed_frame_, 10 );
216- tf_filter_->registerCallback ( boost::bind (&BaseAssembler<T>::msgCallback, this , _1) );
197+ tf_filter_->registerCallback ( boost::bind (&BaseAssembler<T, V >::msgCallback, this , _1) );
217198 }
218199}
219200
220- template <class T >
221- BaseAssembler<T>::~BaseAssembler ()
201+ template <class T , class V >
202+ BaseAssembler<T, V >::~BaseAssembler ()
222203{
223204 if (tf_filter_)
224205 delete tf_filter_;
225206
226207 delete tf_ ;
227208}
228209
229- template <class T >
230- void BaseAssembler<T>::msgCallback(const boost::shared_ptr<const T>& scan_ptr)
210+ template <class T , class V >
211+ void BaseAssembler<T, V >::msgCallback(const boost::shared_ptr<const T>& scan_ptr)
231212{
232213 ROS_DEBUG (" starting msgCallback" );
233214 const T scan = *scan_ptr ;
234215
235- sensor_msgs::PointCloud cur_cloud ;
216+ V cur_cloud ;
236217
237218 // Convert the scan data into a universally known datatype: PointCloud
238219 try
239220 {
240- ConvertToCloud (fixed_frame_, scan, cur_cloud) ; // Convert scan into a point cloud
221+ Convert (fixed_frame_, scan, cur_cloud) ; // Convert scan into V
241222 }
242223 catch (tf::TransformException& ex)
243224 {
@@ -249,125 +230,14 @@ void BaseAssembler<T>::msgCallback(const boost::shared_ptr<const T>& scan_ptr)
249230 scan_hist_mutex_.lock () ;
250231 if (scan_hist_.size () == max_scans_) // Is our deque full?
251232 {
252- total_pts_ -= scan_hist_.front ().points .size () ; // We're removing an elem, so this reduces our total point count
253233 scan_hist_.pop_front () ; // The front of the deque has the oldest elem, so we can get rid of it
254234 }
255235 scan_hist_.push_back (cur_cloud) ; // Add the newest scan to the back of the deque
256- total_pts_ += cur_cloud.points .size () ; // Add the new scan to the running total of points
257-
258- // printf("Scans: %4u Points: %10u\n", scan_hist_.size(), total_pts_) ;
259236
260237 scan_hist_mutex_.unlock () ;
261238 ROS_DEBUG (" done with msgCallback" );
262239}
263240
264- template <class T >
265- bool BaseAssembler<T>::buildCloud(AssembleScans::Request& req, AssembleScans::Response& resp)
266- {
267- ROS_WARN (" Service 'build_cloud' is deprecated. Call 'assemble_scans' instead" );
268- return assembleScans (req, resp);
269- }
270-
271-
272- template <class T >
273- bool BaseAssembler<T>::assembleScans(AssembleScans::Request& req, AssembleScans::Response& resp)
274- {
275- // printf("Starting Service Request\n") ;
276-
277- scan_hist_mutex_.lock () ;
278- // Determine where in our history we actually are
279- unsigned int i = 0 ;
280-
281- // Find the beginning of the request. Probably should be a search
282- while ( i < scan_hist_.size () && // Don't go past end of deque
283- scan_hist_[i].header .stamp < req.begin ) // Keep stepping until we've exceeded the start time
284- {
285- i++ ;
286- }
287- unsigned int start_index = i ;
288-
289- unsigned int req_pts = 0 ; // Keep a total of the points in the current request
290- // Find the end of the request
291- while ( i < scan_hist_.size () && // Don't go past end of deque
292- scan_hist_[i].header .stamp < req.end ) // Don't go past the end-time of the request
293- {
294- req_pts += (scan_hist_[i].points .size ()+downsample_factor_-1 )/downsample_factor_ ;
295- i += downsample_factor_ ;
296- }
297- unsigned int past_end_index = i ;
298-
299- if (start_index == past_end_index)
300- {
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 ) ;
305- }
306- else
307- {
308- // Note: We are assuming that channel information is consistent across multiple scans. If not, then bad things (segfaulting) will happen
309- // Allocate space for the cloud
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++)
314- {
315- resp.cloud .channels [i].name = scan_hist_[start_index].channels [i].name ;
316- resp.cloud .channels [i].values .resize (req_pts) ;
317- }
318- // resp.cloud.header.stamp = req.end ;
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_)
322- {
323-
324- // Sanity check: Each channel should be the same length as the points vector
325- for (unsigned int chan_ind = 0 ; chan_ind < scan_hist_[i].channels .size (); chan_ind++)
326- {
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 ());
329- }
330-
331- for (unsigned int j=0 ; j<scan_hist_[i].points .size (); j+=downsample_factor_)
332- {
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 ;
336-
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] ;
339-
340- cloud_count++ ;
341- }
342- resp.cloud .header .stamp = scan_hist_[i].header .stamp ;
343- }
344- }
345- scan_hist_mutex_.unlock () ;
346-
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 ()) ;
348- return true ;
349- }
350-
351- template <class T >
352- bool BaseAssembler<T>::buildCloud2(AssembleScans2::Request& req, AssembleScans2::Response& resp)
353- {
354- ROS_WARN (" Service 'build_cloud' is deprecated. Call 'assemble_scans' instead" );
355- return assembleScans2 (req, resp);
356241}
357242
358- template <class T >
359- bool BaseAssembler<T>::assembleScans2(AssembleScans2::Request& req, AssembleScans2::Response& resp)
360- {
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);
366-
367- if ( ret )
368- {
369- sensor_msgs::convertPointCloudToPointCloud2 (tmp_res.cloud , resp.cloud );
370- }
371- return ret;
372- }
373- }
243+ #endif /* base_assembler.h */
0 commit comments