Skip to content

Commit 4bcbe31

Browse files
committed
ObservationBuffer stores shared ptrs of observations to avoid copies when queried
Signed-off-by: Fabian König <fabiankoenig@gmail.com>
1 parent 1328541 commit 4bcbe31

File tree

9 files changed

+183
-91
lines changed

9 files changed

+183
-91
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp

Lines changed: 2 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -87,11 +87,6 @@ class ObservationBuffer
8787
std::string sensor_frame,
8888
tf2::Duration tf_tolerance);
8989

90-
/**
91-
* @brief Destructor... cleans up
92-
*/
93-
~ObservationBuffer();
94-
9590
/**
9691
* @brief Transforms a PointCloud to the global frame and buffers it
9792
* <b>Note: The burden is on the user to make sure the transform is available... ie they should use a MessageNotifier</b>
@@ -103,7 +98,7 @@ class ObservationBuffer
10398
* @brief Pushes copies of all current observations onto the end of the vector passed in
10499
* @param observations The vector to be filled
105100
*/
106-
void getObservations(std::vector<Observation> & observations);
101+
void getObservations(std::vector<Observation::ConstSharedPtr> & observations);
107102

108103
/**
109104
* @brief Check if the observation buffer is being update at its expected rate
@@ -146,7 +141,7 @@ class ObservationBuffer
146141
rclcpp::Time last_updated_;
147142
std::string global_frame_;
148143
std::string sensor_frame_;
149-
std::list<Observation> observation_list_;
144+
std::list<Observation::ConstSharedPtr> observation_list_;
150145
std::string topic_name_;
151146
double min_obstacle_height_, max_obstacle_height_;
152147
std::recursive_mutex lock_; ///< @brief A lock for accessing data in callbacks safely

nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -171,7 +171,7 @@ class ObstacleLayer : public CostmapLayer
171171
const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
172172

173173
// for testing purposes
174-
void addStaticObservation(nav2_costmap_2d::Observation & obs, bool marking, bool clearing);
174+
void addStaticObservation(nav2_costmap_2d::Observation obs, bool marking, bool clearing);
175175
void clearStaticObservations(bool marking, bool clearing);
176176

177177
protected:
@@ -181,15 +181,15 @@ class ObstacleLayer : public CostmapLayer
181181
* @return True if all the observation buffers are current, false otherwise
182182
*/
183183
bool getMarkingObservations(
184-
std::vector<nav2_costmap_2d::Observation> & marking_observations) const;
184+
std::vector<nav2_costmap_2d::Observation::ConstSharedPtr> & marking_observations) const;
185185

186186
/**
187187
* @brief Get the observations used to clear space
188188
* @param clearing_observations A reference to a vector that will be populated with the observations
189189
* @return True if all the observation buffers are current, false otherwise
190190
*/
191191
bool getClearingObservations(
192-
std::vector<nav2_costmap_2d::Observation> & clearing_observations) const;
192+
std::vector<nav2_costmap_2d::Observation::ConstSharedPtr> & clearing_observations) const;
193193

194194
/**
195195
* @brief Clear freespace based on one observation
@@ -247,8 +247,8 @@ class ObstacleLayer : public CostmapLayer
247247
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
248248

249249
// Used only for testing purposes
250-
std::vector<nav2_costmap_2d::Observation> static_clearing_observations_;
251-
std::vector<nav2_costmap_2d::Observation> static_marking_observations_;
250+
std::vector<nav2_costmap_2d::Observation::ConstSharedPtr> static_clearing_observations_;
251+
std::vector<nav2_costmap_2d::Observation::ConstSharedPtr> static_marking_observations_;
252252

253253
bool rolling_window_;
254254
bool was_reset_;

nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -218,7 +218,7 @@ unsigned char CostmapFilter::getMaskCost(
218218
{
219219
const unsigned int index = my * filter_mask->info.width + mx;
220220

221-
const char data = filter_mask->data[index];
221+
const auto data = filter_mask->data[index];
222222
if (data == nav2_util::OCC_GRID_UNKNOWN) {
223223
return NO_INFORMATION;
224224
} else {

nav2_costmap_2d/plugins/obstacle_layer.cpp

Lines changed: 30 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -199,15 +199,13 @@ void ObstacleLayer::onInitialize()
199199

200200
// create an observation buffer
201201
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,
206204
min_obstacle_height,
207205
max_obstacle_height, obstacle_max_range, obstacle_min_range, raytrace_max_range,
208206
raytrace_min_range, *tf_,
209207
global_frame_,
210-
sensor_frame, tf2::durationFromSec(transform_tolerance))));
208+
sensor_frame, tf2::durationFromSec(transform_tolerance)));
211209

212210
// check if we'll add this buffer to our marking observation buffers
213211
if (marking) {
@@ -333,7 +331,7 @@ ObstacleLayer::dynamicParametersCallback(
333331
void
334332
ObstacleLayer::laserScanCallback(
335333
sensor_msgs::msg::LaserScan::ConstSharedPtr message,
336-
const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
334+
const std::shared_ptr<ObservationBuffer> & buffer)
337335
{
338336
// project the laser into a point cloud
339337
sensor_msgs::msg::PointCloud2 cloud;
@@ -367,7 +365,7 @@ ObstacleLayer::laserScanCallback(
367365
void
368366
ObstacleLayer::laserScanValidInfCallback(
369367
sensor_msgs::msg::LaserScan::ConstSharedPtr raw_message,
370-
const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer)
368+
const std::shared_ptr<ObservationBuffer> & buffer)
371369
{
372370
// Filter positive infinities ("Inf"s) to max_range.
373371
float epsilon = 0.0001; // a tenth of a millimeter
@@ -433,7 +431,7 @@ ObstacleLayer::updateBounds(
433431
useExtraBounds(min_x, min_y, max_x, max_y);
434432

435433
bool current = true;
436-
std::vector<Observation> observations, clearing_observations;
434+
std::vector<Observation::ConstSharedPtr> observations, clearing_observations;
437435

438436
// get the marking observations
439437
current = current && getMarkingObservations(observations);
@@ -445,15 +443,13 @@ ObstacleLayer::updateBounds(
445443
current_ = current;
446444

447445
// 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);
450448
}
451449

452450
// 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;
457453

458454
const sensor_msgs::msg::PointCloud2 & cloud = obs.cloud_;
459455

@@ -566,14 +562,15 @@ ObstacleLayer::updateCosts(
566562

567563
void
568564
ObstacleLayer::addStaticObservation(
569-
nav2_costmap_2d::Observation & obs,
565+
nav2_costmap_2d::Observation obs,
570566
bool marking, bool clearing)
571567
{
568+
const auto observation = Observation::make_shared(std::move(obs));
572569
if (marking) {
573-
static_marking_observations_.push_back(obs);
570+
static_marking_observations_.push_back(observation);
574571
}
575572
if (clearing) {
576-
static_clearing_observations_.push_back(obs);
573+
static_clearing_observations_.push_back(observation);
577574
}
578575
}
579576

@@ -589,15 +586,16 @@ ObstacleLayer::clearStaticObservations(bool marking, bool clearing)
589586
}
590587

591588
bool
592-
ObstacleLayer::getMarkingObservations(std::vector<Observation> & marking_observations) const
589+
ObstacleLayer::getMarkingObservations(
590+
std::vector<Observation::ConstSharedPtr> & marking_observations) const
593591
{
594592
bool current = true;
595593
// 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();
601599
}
602600
marking_observations.insert(
603601
marking_observations.end(),
@@ -606,15 +604,16 @@ ObstacleLayer::getMarkingObservations(std::vector<Observation> & marking_observa
606604
}
607605

608606
bool
609-
ObstacleLayer::getClearingObservations(std::vector<Observation> & clearing_observations) const
607+
ObstacleLayer::getClearingObservations(
608+
std::vector<Observation::ConstSharedPtr> & clearing_observations) const
610609
{
611610
bool current = true;
612611
// 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();
618617
}
619618
clearing_observations.insert(
620619
clearing_observations.end(),
@@ -766,10 +765,8 @@ ObstacleLayer::reset()
766765
void
767766
ObstacleLayer::resetBuffersLastUpdated()
768767
{
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();
773770
}
774771
}
775772

nav2_costmap_2d/plugins/voxel_layer.cpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -163,7 +163,7 @@ void VoxelLayer::updateBounds(
163163
useExtraBounds(min_x, min_y, max_x, max_y);
164164

165165
bool current = true;
166-
std::vector<Observation> observations, clearing_observations;
166+
std::vector<Observation::ConstSharedPtr> observations, clearing_observations;
167167

168168
// get the marking observations
169169
current = getMarkingObservations(observations) && current;
@@ -175,15 +175,13 @@ void VoxelLayer::updateBounds(
175175
current_ = current;
176176

177177
// raytrace freespace
178-
for (unsigned int i = 0; i < clearing_observations.size(); ++i) {
179-
raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
178+
for (const auto & clearing_observation : clearing_observations) {
179+
raytraceFreespace(*clearing_observation, min_x, min_y, max_x, max_y);
180180
}
181181

182182
// place the new obstacles into a priority queue... each with a priority of zero to begin with
183-
for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end();
184-
++it)
185-
{
186-
const Observation & obs = *it;
183+
for (const auto & observation : observations) {
184+
const Observation & obs = *observation;
187185

188186
const sensor_msgs::msg::PointCloud2 & cloud = obs.cloud_;
189187

nav2_costmap_2d/src/observation_buffer.cpp

Lines changed: 21 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -76,22 +76,18 @@ ObservationBuffer::ObservationBuffer(
7676
last_updated_ = node->now();
7777
}
7878

79-
ObservationBuffer::~ObservationBuffer()
80-
{
81-
}
82-
8379
void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud)
8480
{
8581
geometry_msgs::msg::PointStamped global_origin;
8682

87-
// create a new observation on the list to be populated
88-
observation_list_.push_front(Observation());
89-
9083
// check whether the origin frame has been set explicitly
9184
// or whether we should get it from the cloud
9285
std::string origin_frame = sensor_frame_ == "" ? cloud.header.frame_id : sensor_frame_;
9386

9487
try {
88+
// create a new observation to add to the list after being populated
89+
auto observation = Observation::make_shared();
90+
9591
// given these observations come from sensors...
9692
// we'll need to store the origin pt of the sensor
9793
geometry_msgs::msg::PointStamped local_origin;
@@ -101,14 +97,14 @@ void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud)
10197
local_origin.point.y = 0;
10298
local_origin.point.z = 0;
10399
tf2_buffer_.transform(local_origin, global_origin, global_frame_, tf_tolerance_);
104-
tf2::convert(global_origin.point, observation_list_.front().origin_);
100+
tf2::convert(global_origin.point, observation->origin_);
105101

106102
// make sure to pass on the raytrace/obstacle range
107103
// of the observation buffer to the observations
108-
observation_list_.front().raytrace_max_range_ = raytrace_max_range_;
109-
observation_list_.front().raytrace_min_range_ = raytrace_min_range_;
110-
observation_list_.front().obstacle_max_range_ = obstacle_max_range_;
111-
observation_list_.front().obstacle_min_range_ = obstacle_min_range_;
104+
observation->raytrace_max_range_ = raytrace_max_range_;
105+
observation->raytrace_min_range_ = raytrace_min_range_;
106+
observation->obstacle_max_range_ = obstacle_max_range_;
107+
observation->obstacle_min_range_ = obstacle_min_range_;
112108

113109
sensor_msgs::msg::PointCloud2 global_frame_cloud;
114110

@@ -118,7 +114,7 @@ void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud)
118114

119115
// now we need to remove observations from the cloud that are below
120116
// or above our height thresholds
121-
sensor_msgs::msg::PointCloud2 & observation_cloud = (observation_list_.front().cloud_);
117+
sensor_msgs::msg::PointCloud2 & observation_cloud = observation->cloud_;
122118
observation_cloud.height = global_frame_cloud.height;
123119
observation_cloud.width = global_frame_cloud.width;
124120
observation_cloud.fields = global_frame_cloud.fields;
@@ -153,9 +149,10 @@ void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud)
153149
modifier.resize(point_count);
154150
observation_cloud.header.stamp = cloud.header.stamp;
155151
observation_cloud.header.frame_id = global_frame_cloud.header.frame_id;
152+
153+
observation_list_.push_front(std::move(observation));
156154
} catch (tf2::TransformException & ex) {
157155
// if an exception occurs, we need to remove the empty observation from the list
158-
observation_list_.pop_front();
159156
RCLCPP_ERROR(
160157
logger_,
161158
"TF Exception that should never happen for sensor frame: %s, cloud frame: %s, %s",
@@ -171,40 +168,27 @@ void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud)
171168
purgeStaleObservations();
172169
}
173170

174-
// returns a copy of the observations
175-
void ObservationBuffer::getObservations(std::vector<Observation> & observations)
171+
// appends the observations from the buffer to the passed vector
172+
void ObservationBuffer::getObservations(std::vector<Observation::ConstSharedPtr> & observations)
176173
{
177174
// first... let's make sure that we don't have any stale observations
178175
purgeStaleObservations();
179176

180-
// now we'll just copy the observations for the caller
181-
std::list<Observation>::iterator obs_it;
182-
for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it) {
183-
observations.push_back(*obs_it);
184-
}
177+
// now we'll just copy the observation ptrs for the caller
178+
observations.insert(observations.end(), observation_list_.cbegin(), observation_list_.cend());
185179
}
186180

187181
void ObservationBuffer::purgeStaleObservations()
188182
{
189183
if (!observation_list_.empty()) {
190-
std::list<Observation>::iterator obs_it = observation_list_.begin();
191184
// if we're keeping observations for no time... then we'll only keep one observation
192185
if (observation_keep_time_ == rclcpp::Duration(0.0s)) {
193-
observation_list_.erase(++obs_it, observation_list_.end());
194-
return;
195-
}
196-
197-
// otherwise... we'll have to loop through the observations to see which ones are stale
198-
for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it) {
199-
Observation & obs = *obs_it;
200-
// check if the observation is out of date... and if it is,
201-
// remove it and those that follow from the list
202-
if ((clock_->now() - obs.cloud_->header.stamp) >
203-
observation_keep_time_)
204-
{
205-
observation_list_.erase(obs_it, observation_list_.end());
206-
return;
207-
}
186+
observation_list_.erase(std::next(observation_list_.begin()), observation_list_.end());
187+
} else {
188+
// otherwise remove all observations that are older then the keep time
189+
observation_list_.remove_if([now = clock_->now(), this](const auto observation){
190+
return (now - observation->cloud_.header.stamp) > observation_keep_time_;
191+
});
208192
}
209193
}
210194
}

nav2_costmap_2d/test/testing_helper.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ void addObservation(
130130
nav2_costmap_2d::Observation obs(std::move(p), std::move(cloud), obstacle_max_range,
131131
obstacle_min_range,
132132
raytrace_max_range, raytrace_min_range);
133-
olayer->addStaticObservation(obs, marking, clearing);
133+
olayer->addStaticObservation(std::move(obs), marking, clearing);
134134
}
135135

136136
void addInflationLayer(

nav2_costmap_2d/test/unit/CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -62,3 +62,8 @@ ament_add_gtest(lifecycle_test lifecycle_test.cpp)
6262
target_link_libraries(lifecycle_test
6363
nav2_costmap_2d_core
6464
)
65+
66+
ament_add_gtest(observation_buffer_test observation_buffer_test.cpp)
67+
target_link_libraries(observation_buffer_test
68+
nav2_costmap_2d_core
69+
)

0 commit comments

Comments
 (0)