@@ -199,15 +199,13 @@ void ObstacleLayer::onInitialize()
199
199
200
200
// create an observation buffer
201
201
observation_buffers_.push_back (
202
- std::shared_ptr<ObservationBuffer
203
- >(
204
- new ObservationBuffer (
205
- node, topic, observation_keep_time, expected_update_rate,
202
+ std::make_shared<ObservationBuffer>(node, topic, observation_keep_time,
203
+ expected_update_rate,
206
204
min_obstacle_height,
207
205
max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
208
206
raytrace_min_range, *tf_,
209
207
global_frame_,
210
- sensor_frame, tf2::durationFromSec (transform_tolerance)))) ;
208
+ sensor_frame, tf2::durationFromSec (transform_tolerance)));
211
209
212
210
// check if we'll add this buffer to our marking observation buffers
213
211
if (marking) {
@@ -333,7 +331,7 @@ ObstacleLayer::dynamicParametersCallback(
333
331
void
334
332
ObstacleLayer::laserScanCallback (
335
333
sensor_msgs::msg::LaserScan::ConstSharedPtr message,
336
- const std::shared_ptr<nav2_costmap_2d:: ObservationBuffer> & buffer)
334
+ const std::shared_ptr<ObservationBuffer> & buffer)
337
335
{
338
336
// project the laser into a point cloud
339
337
sensor_msgs::msg::PointCloud2 cloud;
@@ -367,7 +365,7 @@ ObstacleLayer::laserScanCallback(
367
365
void
368
366
ObstacleLayer::laserScanValidInfCallback (
369
367
sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
370
- const std::shared_ptr<nav2_costmap_2d:: ObservationBuffer> & buffer)
368
+ const std::shared_ptr<ObservationBuffer> & buffer)
371
369
{
372
370
// Filter positive infinities ("Inf"s) to max_range.
373
371
float epsilon = 0.0001 ; // a tenth of a millimeter
@@ -433,7 +431,7 @@ ObstacleLayer::updateBounds(
433
431
useExtraBounds (min_x, min_y, max_x, max_y);
434
432
435
433
bool current = true ;
436
- std::vector<Observation> observations, clearing_observations;
434
+ std::vector<Observation::ConstSharedPtr > observations, clearing_observations;
437
435
438
436
// get the marking observations
439
437
current = current && getMarkingObservations (observations);
@@ -445,15 +443,13 @@ ObstacleLayer::updateBounds(
445
443
current_ = current;
446
444
447
445
// raytrace freespace
448
- for (unsigned int i = 0 ; i < clearing_observations. size (); ++i ) {
449
- raytraceFreespace (clearing_observations[i] , min_x, min_y, max_x, max_y);
446
+ for (const auto & clearing_observation : clearing_observations) {
447
+ raytraceFreespace (*clearing_observation , min_x, min_y, max_x, max_y);
450
448
}
451
449
452
450
// place the new obstacles into a priority queue... each with a priority of zero to begin with
453
- for (std::vector<Observation>::const_iterator it = observations.begin ();
454
- it != observations.end (); ++it)
455
- {
456
- const Observation & obs = *it;
451
+ for (const auto & observation : observations) {
452
+ const Observation & obs = *observation;
457
453
458
454
const sensor_msgs::msg::PointCloud2 & cloud = obs.cloud_ ;
459
455
@@ -566,14 +562,15 @@ ObstacleLayer::updateCosts(
566
562
567
563
void
568
564
ObstacleLayer::addStaticObservation (
569
- nav2_costmap_2d::Observation & obs,
565
+ nav2_costmap_2d::Observation obs,
570
566
bool marking, bool clearing)
571
567
{
568
+ const auto observation = Observation::make_shared (std::move (obs));
572
569
if (marking) {
573
- static_marking_observations_.push_back (obs );
570
+ static_marking_observations_.push_back (observation );
574
571
}
575
572
if (clearing) {
576
- static_clearing_observations_.push_back (obs );
573
+ static_clearing_observations_.push_back (observation );
577
574
}
578
575
}
579
576
@@ -589,15 +586,16 @@ ObstacleLayer::clearStaticObservations(bool marking, bool clearing)
589
586
}
590
587
591
588
bool
592
- ObstacleLayer::getMarkingObservations (std::vector<Observation> & marking_observations) const
589
+ ObstacleLayer::getMarkingObservations (
590
+ std::vector<Observation::ConstSharedPtr> & marking_observations) const
593
591
{
594
592
bool current = true ;
595
593
// get the marking observations
596
- for (unsigned int i = 0 ; i < marking_buffers_. size (); ++i ) {
597
- marking_buffers_[i] ->lock ();
598
- marking_buffers_[i] ->getObservations (marking_observations);
599
- current = marking_buffers_[i] ->isCurrent () && current;
600
- marking_buffers_[i] ->unlock ();
594
+ for (const auto & marking_buffer : marking_buffers_) {
595
+ marking_buffer ->lock ();
596
+ marking_buffer ->getObservations (marking_observations);
597
+ current = marking_buffer ->isCurrent () && current;
598
+ marking_buffer ->unlock ();
601
599
}
602
600
marking_observations.insert (
603
601
marking_observations.end (),
@@ -606,15 +604,16 @@ ObstacleLayer::getMarkingObservations(std::vector<Observation> & marking_observa
606
604
}
607
605
608
606
bool
609
- ObstacleLayer::getClearingObservations (std::vector<Observation> & clearing_observations) const
607
+ ObstacleLayer::getClearingObservations (
608
+ std::vector<Observation::ConstSharedPtr> & clearing_observations) const
610
609
{
611
610
bool current = true ;
612
611
// get the clearing observations
613
- for (unsigned int i = 0 ; i < clearing_buffers_. size (); ++i ) {
614
- clearing_buffers_[i] ->lock ();
615
- clearing_buffers_[i] ->getObservations (clearing_observations);
616
- current = clearing_buffers_[i] ->isCurrent () && current;
617
- clearing_buffers_[i] ->unlock ();
612
+ for (const auto & clearing_buffer : clearing_buffers_) {
613
+ clearing_buffer ->lock ();
614
+ clearing_buffer ->getObservations (clearing_observations);
615
+ current = clearing_buffer ->isCurrent () && current;
616
+ clearing_buffer ->unlock ();
618
617
}
619
618
clearing_observations.insert (
620
619
clearing_observations.end (),
@@ -766,10 +765,8 @@ ObstacleLayer::reset()
766
765
void
767
766
ObstacleLayer::resetBuffersLastUpdated ()
768
767
{
769
- for (unsigned int i = 0 ; i < observation_buffers_.size (); ++i) {
770
- if (observation_buffers_[i]) {
771
- observation_buffers_[i]->resetLastUpdated ();
772
- }
768
+ for (const auto & observation_buffer : observation_buffers_) {
769
+ observation_buffer->resetLastUpdated ();
773
770
}
774
771
}
775
772
0 commit comments