Skip to content

Commit 66cc6cb

Browse files
author
Radu Rusu
committed
fixed all warnings
git-svn-id: https://code.ros.org/svn/ros-pkg/stacks/laser_pipeline/trunk@29627 eb33c2ac-9c88-4c90-87e0-44a10359b0c3
1 parent 89f2a51 commit 66cc6cb

File tree

3 files changed

+15
-15
lines changed

3 files changed

+15
-15
lines changed

include/laser_assembler/base_assembler.h

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -242,11 +242,11 @@ void BaseAssembler<T>::msgCallback(const boost::shared_ptr<const T>& scan_ptr)
242242
scan_hist_mutex_.lock() ;
243243
if (scan_hist_.size() == max_scans_) // Is our deque full?
244244
{
245-
total_pts_ -= scan_hist_.front().get_points_size() ; // We're removing an elem, so this reduces our total point count
245+
total_pts_ -= scan_hist_.front().points.size () ; // We're removing an elem, so this reduces our total point count
246246
scan_hist_.pop_front() ; // The front of the deque has the oldest elem, so we can get rid of it
247247
}
248248
scan_hist_.push_back(cur_cloud) ; // Add the newest scan to the back of the deque
249-
total_pts_ += cur_cloud.get_points_size() ; // Add the new scan to the running total of points
249+
total_pts_ += cur_cloud.points.size () ; // Add the new scan to the running total of points
250250

251251
//printf("Scans: %4u Points: %10u\n", scan_hist_.size(), total_pts_) ;
252252

@@ -284,7 +284,7 @@ bool BaseAssembler<T>::assembleScans(AssembleScans::Request& req, AssembleScans:
284284
while ( i < scan_hist_.size() && // Don't go past end of deque
285285
scan_hist_[i].header.stamp < req.end ) // Don't go past the end-time of the request
286286
{
287-
req_pts += (scan_hist_[i].get_points_size()+downsample_factor_-1)/downsample_factor_ ;
287+
req_pts += (scan_hist_[i].points.size ()+downsample_factor_-1)/downsample_factor_ ;
288288
i += downsample_factor_ ;
289289
}
290290
unsigned int past_end_index = i ;
@@ -293,20 +293,20 @@ bool BaseAssembler<T>::assembleScans(AssembleScans::Request& req, AssembleScans:
293293
{
294294
resp.cloud.header.frame_id = fixed_frame_ ;
295295
resp.cloud.header.stamp = req.end ;
296-
resp.cloud.set_points_size(0) ;
297-
resp.cloud.set_channels_size(0) ;
296+
resp.cloud.points.resize (0) ;
297+
resp.cloud.channels.resize (0) ;
298298
}
299299
else
300300
{
301301
// Note: We are assuming that channel information is consistent across multiple scans. If not, then bad things (segfaulting) will happen
302302
// Allocate space for the cloud
303-
resp.cloud.set_points_size( req_pts ) ;
304-
const unsigned int num_channels = scan_hist_[start_index].get_channels_size() ;
305-
resp.cloud.set_channels_size(num_channels) ;
303+
resp.cloud.points.resize (req_pts);
304+
const unsigned int num_channels = scan_hist_[start_index].channels.size ();
305+
resp.cloud.channels.resize (num_channels) ;
306306
for (i = 0; i<num_channels; i++)
307307
{
308308
resp.cloud.channels[i].name = scan_hist_[start_index].channels[i].name ;
309-
resp.cloud.channels[i].set_values_size(req_pts) ;
309+
resp.cloud.channels[i].values.resize (req_pts) ;
310310
}
311311
//resp.cloud.header.stamp = req.end ;
312312
resp.cloud.header.frame_id = fixed_frame_ ;
@@ -317,11 +317,11 @@ bool BaseAssembler<T>::assembleScans(AssembleScans::Request& req, AssembleScans:
317317
// Sanity check: Each channel should be the same length as the points vector
318318
for (unsigned int chan_ind = 0; chan_ind < scan_hist_[i].channels.size(); chan_ind++)
319319
{
320-
if (scan_hist_[i].get_points_size() != scan_hist_[i].channels[chan_ind].values.size())
321-
ROS_FATAL("Trying to add a malformed point cloud. Cloud has %u points, but channel %u has %u elems", scan_hist_[i].get_points_size(), chan_ind, scan_hist_[i].channels[chan_ind].get_values_size());
320+
if (scan_hist_[i].points.size () != scan_hist_[i].channels[chan_ind].values.size())
321+
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 ());
322322
}
323323

324-
for(unsigned int j=0; j<scan_hist_[i].get_points_size(); j+=downsample_factor_)
324+
for(unsigned int j=0; j<scan_hist_[i].points.size (); j+=downsample_factor_)
325325
{
326326
resp.cloud.points[cloud_count].x = scan_hist_[i].points[j].x ;
327327
resp.cloud.points[cloud_count].y = scan_hist_[i].points[j].y ;
@@ -337,7 +337,7 @@ bool BaseAssembler<T>::assembleScans(AssembleScans::Request& req, AssembleScans:
337337
}
338338
scan_hist_mutex_.unlock() ;
339339

340-
ROS_DEBUG("Point Cloud Results: Aggregated from index %u->%u. BufferSize: %lu. Points in cloud: %u", start_index, past_end_index, scan_hist_.size(), resp.cloud.get_points_size()) ;
340+
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 ()) ;
341341
return true ;
342342
}
343343

src/laser_scan_assembler.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ class LaserScanAssembler : public BaseAssembler<sensor_msgs::LaserScan>
7575

7676
unsigned int GetPointsInScan(const sensor_msgs::LaserScan& scan)
7777
{
78-
return scan.get_ranges_size();
78+
return (scan.ranges.size ());
7979
}
8080

8181
void ConvertToCloud(const string& fixed_frame_id, const sensor_msgs::LaserScan& scan_in, sensor_msgs::PointCloud& cloud_out)

src/point_cloud_assembler.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ class PointCloudAssembler : public BaseAssembler<sensor_msgs::PointCloud>
6262

6363
unsigned int GetPointsInScan(const sensor_msgs::PointCloud& scan)
6464
{
65-
return scan.get_points_size() ;
65+
return (scan.points.size ());
6666
}
6767

6868
void ConvertToCloud(const string& fixed_frame_id, const sensor_msgs::PointCloud& scan_in, sensor_msgs::PointCloud& cloud_out)

0 commit comments

Comments
 (0)