@@ -202,15 +202,13 @@ void ObstacleLayer::onInitialize()
202
202
203
203
// create an observation buffer
204
204
observation_buffers_.push_back (
205
- std::shared_ptr<ObservationBuffer
206
- >(
207
- new ObservationBuffer (
208
- node, topic, observation_keep_time, expected_update_rate,
205
+ std::make_shared<ObservationBuffer>(node, topic, observation_keep_time,
206
+ expected_update_rate,
209
207
min_obstacle_height,
210
208
max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
211
209
raytrace_min_range, *tf_,
212
210
global_frame_,
213
- sensor_frame, tf2::durationFromSec (transform_tolerance)))) ;
211
+ sensor_frame, tf2::durationFromSec (transform_tolerance)));
214
212
215
213
// check if we'll add this buffer to our marking observation buffers
216
214
if (marking) {
@@ -388,7 +386,7 @@ ObstacleLayer::dynamicParametersCallback(
388
386
void
389
387
ObstacleLayer::laserScanCallback (
390
388
sensor_msgs::msg::LaserScan::ConstSharedPtr message,
391
- const std::shared_ptr<nav2_costmap_2d:: ObservationBuffer> & buffer)
389
+ const std::shared_ptr<ObservationBuffer> & buffer)
392
390
{
393
391
// project the laser into a point cloud
394
392
sensor_msgs::msg::PointCloud2 cloud;
@@ -422,7 +420,7 @@ ObstacleLayer::laserScanCallback(
422
420
void
423
421
ObstacleLayer::laserScanValidInfCallback (
424
422
sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
425
- const std::shared_ptr<nav2_costmap_2d:: ObservationBuffer> & buffer)
423
+ const std::shared_ptr<ObservationBuffer> & buffer)
426
424
{
427
425
// Filter positive infinities ("Inf"s) to max_range.
428
426
float epsilon = 0.0001 ; // a tenth of a millimeter
@@ -488,7 +486,7 @@ ObstacleLayer::updateBounds(
488
486
useExtraBounds (min_x, min_y, max_x, max_y);
489
487
490
488
bool current = true ;
491
- std::vector<Observation> observations, clearing_observations;
489
+ std::vector<Observation::ConstSharedPtr > observations, clearing_observations;
492
490
493
491
// get the marking observations
494
492
current = current && getMarkingObservations (observations);
@@ -500,15 +498,13 @@ ObstacleLayer::updateBounds(
500
498
current_ = current;
501
499
502
500
// raytrace freespace
503
- for (unsigned int i = 0 ; i < clearing_observations. size (); ++i ) {
504
- raytraceFreespace (clearing_observations[i] , min_x, min_y, max_x, max_y);
501
+ for (const auto & clearing_observation : clearing_observations) {
502
+ raytraceFreespace (*clearing_observation , min_x, min_y, max_x, max_y);
505
503
}
506
504
507
505
// place the new obstacles into a priority queue... each with a priority of zero to begin with
508
- for (std::vector<Observation>::const_iterator it = observations.begin ();
509
- it != observations.end (); ++it)
510
- {
511
- const Observation & obs = *it;
506
+ for (const auto & observation : observations) {
507
+ const Observation & obs = *observation;
512
508
513
509
const sensor_msgs::msg::PointCloud2 & cloud = obs.cloud_ ;
514
510
@@ -621,14 +617,15 @@ ObstacleLayer::updateCosts(
621
617
622
618
void
623
619
ObstacleLayer::addStaticObservation (
624
- nav2_costmap_2d::Observation & obs,
620
+ nav2_costmap_2d::Observation obs,
625
621
bool marking, bool clearing)
626
622
{
623
+ const auto observation = Observation::make_shared (std::move (obs));
627
624
if (marking) {
628
- static_marking_observations_.push_back (obs );
625
+ static_marking_observations_.push_back (observation );
629
626
}
630
627
if (clearing) {
631
- static_clearing_observations_.push_back (obs );
628
+ static_clearing_observations_.push_back (observation );
632
629
}
633
630
}
634
631
@@ -644,15 +641,16 @@ ObstacleLayer::clearStaticObservations(bool marking, bool clearing)
644
641
}
645
642
646
643
bool
647
- ObstacleLayer::getMarkingObservations (std::vector<Observation> & marking_observations) const
644
+ ObstacleLayer::getMarkingObservations (
645
+ std::vector<Observation::ConstSharedPtr> & marking_observations) const
648
646
{
649
647
bool current = true ;
650
648
// get the marking observations
651
- for (unsigned int i = 0 ; i < marking_buffers_. size (); ++i ) {
652
- marking_buffers_[i] ->lock ();
653
- marking_buffers_[i] ->getObservations (marking_observations);
654
- current = marking_buffers_[i] ->isCurrent () && current;
655
- marking_buffers_[i] ->unlock ();
649
+ for (const auto & marking_buffer : marking_buffers_) {
650
+ marking_buffer ->lock ();
651
+ marking_buffer ->getObservations (marking_observations);
652
+ current = marking_buffer ->isCurrent () && current;
653
+ marking_buffer ->unlock ();
656
654
}
657
655
marking_observations.insert (
658
656
marking_observations.end (),
@@ -661,15 +659,16 @@ ObstacleLayer::getMarkingObservations(std::vector<Observation> & marking_observa
661
659
}
662
660
663
661
bool
664
- ObstacleLayer::getClearingObservations (std::vector<Observation> & clearing_observations) const
662
+ ObstacleLayer::getClearingObservations (
663
+ std::vector<Observation::ConstSharedPtr> & clearing_observations) const
665
664
{
666
665
bool current = true ;
667
666
// get the clearing observations
668
- for (unsigned int i = 0 ; i < clearing_buffers_. size (); ++i ) {
669
- clearing_buffers_[i] ->lock ();
670
- clearing_buffers_[i] ->getObservations (clearing_observations);
671
- current = clearing_buffers_[i] ->isCurrent () && current;
672
- clearing_buffers_[i] ->unlock ();
667
+ for (const auto & clearing_buffer : clearing_buffers_) {
668
+ clearing_buffer ->lock ();
669
+ clearing_buffer ->getObservations (clearing_observations);
670
+ current = clearing_buffer ->isCurrent () && current;
671
+ clearing_buffer ->unlock ();
673
672
}
674
673
clearing_observations.insert (
675
674
clearing_observations.end (),
@@ -821,10 +820,8 @@ ObstacleLayer::reset()
821
820
void
822
821
ObstacleLayer::resetBuffersLastUpdated ()
823
822
{
824
- for (unsigned int i = 0 ; i < observation_buffers_.size (); ++i) {
825
- if (observation_buffers_[i]) {
826
- observation_buffers_[i]->resetLastUpdated ();
827
- }
823
+ for (const auto & observation_buffer : observation_buffers_) {
824
+ observation_buffer->resetLastUpdated ();
828
825
}
829
826
}
830
827
0 commit comments