Skip to content

Commit 22f787a

Browse files
committed
Removing deprecation warnings
git-svn-id: https://code.ros.org/svn/ros-pkg/stacks/laser_pipeline/trunk@35255 eb33c2ac-9c88-4c90-87e0-44a10359b0c3
1 parent f8ca485 commit 22f787a

File tree

5 files changed

+16
-16
lines changed

5 files changed

+16
-16
lines changed

examples/periodic_snapshotter.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,7 @@ class PeriodicSnapshotter
8989
// Make the service call
9090
if (client_.call(srv))
9191
{
92-
ROS_INFO("Published Cloud with %u points", srv.response.cloud.get_points_size()) ;
92+
ROS_INFO("Published Cloud with %u points", (uint32_t)(srv.response.cloud.points.size())) ;
9393
pub_.publish(srv.response.cloud);
9494
}
9595
else

include/laser_assembler/base_assembler_srv.h

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

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

@@ -279,7 +279,7 @@ bool BaseAssemblerSrv<T>::buildCloud(AssembleScans::Request& req, AssembleScans:
279279
while ( i < scan_hist_.size() && // Don't go past end of deque
280280
scan_hist_[i].header.stamp < req.end ) // Don't go past the end-time of the request
281281
{
282-
req_pts += (scan_hist_[i].get_points_size()+downsample_factor_-1)/downsample_factor_ ;
282+
req_pts += (scan_hist_[i].points.size()+downsample_factor_-1)/downsample_factor_ ;
283283
i += downsample_factor_ ;
284284
}
285285
unsigned int past_end_index = i ;
@@ -288,27 +288,27 @@ bool BaseAssemblerSrv<T>::buildCloud(AssembleScans::Request& req, AssembleScans:
288288
{
289289
resp.cloud.header.frame_id = fixed_frame_ ;
290290
resp.cloud.header.stamp = req.end ;
291-
resp.cloud.set_points_size(0) ;
292-
resp.cloud.set_channels_size(0) ;
291+
resp.cloud.points.resize(0) ;
292+
resp.cloud.channels.resize(0) ;
293293
}
294294
else
295295
{
296296
// Note: We are assuming that channel information is consistent across multiple scans. If not, then bad things (segfaulting) will happen
297297
// Allocate space for the cloud
298-
resp.cloud.set_points_size( req_pts ) ;
299-
const unsigned int num_channels = scan_hist_[start_index].get_channels_size() ;
300-
resp.cloud.set_channels_size(num_channels) ;
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) ;
301301
for (i = 0; i<num_channels; i++)
302302
{
303303
resp.cloud.channels[i].name = scan_hist_[start_index].channels[i].name ;
304-
resp.cloud.channels[i].set_values_size(req_pts) ;
304+
resp.cloud.channels[i].values.resize(req_pts) ;
305305
}
306306
//resp.cloud.header.stamp = req.end ;
307307
resp.cloud.header.frame_id = fixed_frame_ ;
308308
unsigned int cloud_count = 0 ;
309309
for (i=start_index; i<past_end_index; i+=downsample_factor_)
310310
{
311-
for(unsigned int j=0; j<scan_hist_[i].get_points_size(); j+=downsample_factor_)
311+
for(unsigned int j=0; j<scan_hist_[i].points.size(); j+=downsample_factor_)
312312
{
313313
resp.cloud.points[cloud_count].x = scan_hist_[i].points[j].x ;
314314
resp.cloud.points[cloud_count].y = scan_hist_[i].points[j].y ;

src/laser_scan_assembler_srv.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ class LaserScanAssemblerSrv : public BaseAssemblerSrv<sensor_msgs::LaserScan>
7373

7474
unsigned int GetPointsInScan(const sensor_msgs::LaserScan& scan)
7575
{
76-
return scan.get_ranges_size();
76+
return scan.ranges.size();
7777
}
7878

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

src/point_cloud_assembler_srv.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ class PointCloudAssemblerSrv : public BaseAssemblerSrv<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)

test/test_assembler.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -81,9 +81,9 @@ class TestAssembler : public testing::Test
8181
assemble_scans.request.begin = start_time_;
8282
assemble_scans.request.end = scan_msg->header.stamp;
8383
EXPECT_TRUE(ros::service::call(SERVICE_NAME, assemble_scans));
84-
if(assemble_scans.response.cloud.get_points_size() > 0)
84+
if(assemble_scans.response.cloud.points.size() > 0)
8585
{
86-
ROS_INFO("Got a cloud with [%u] points. Saving the cloud", assemble_scans.response.cloud.get_points_size());
86+
ROS_INFO("Got a cloud with [%u] points. Saving the cloud", (uint32_t)(assemble_scans.response.cloud.points.size()));
8787
cloud_ = assemble_scans.response.cloud;
8888
got_cloud_ = true;
8989
cloud_condition_.notify_all();
@@ -120,7 +120,7 @@ TEST_F(TestAssembler, non_zero_cloud_test)
120120
cloud_condition_.timed_wait(lock, boost::posix_time::milliseconds(1000.0f));
121121
}
122122

123-
EXPECT_LT((unsigned int) 0, cloud_.get_points_size());
123+
EXPECT_LT((unsigned int) 0, cloud_.points.size());
124124

125125
SUCCEED();
126126
}

0 commit comments

Comments
 (0)