Skip to content

Commit 0fcbd7c

Browse files
authored
Added new costmap buffer to resize map safely (#1837)
* Added new costmap buffer to resize map safely Signed-off-by: Aitor Miguel Blanco <aitormibl@gmail.com> * Update map if the layer is not being processed. Signed-off-by: Aitor Miguel Blanco <aitormibl@gmail.com> * Updated bool name and added buffer initialization Signed-off-by: Aitor Miguel Blanco <aitormibl@gmail.com>
1 parent f1d7f0d commit 0fcbd7c

File tree

2 files changed

+26
-3
lines changed

2 files changed

+26
-3
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -111,6 +111,8 @@ class StaticLayer : public CostmapLayer
111111
bool trinary_costmap_;
112112
bool map_received_{false};
113113
tf2::Duration transform_tolerance_;
114+
std::atomic<bool> update_in_progress_;
115+
nav_msgs::msg::OccupancyGrid::SharedPtr map_buffer_;
114116
};
115117

116118
} // namespace nav2_costmap_2d

nav2_costmap_2d/plugins/static_layer.cpp

Lines changed: 24 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@ namespace nav2_costmap_2d
5858
{
5959

6060
StaticLayer::StaticLayer()
61+
: map_buffer_(nullptr)
6162
{
6263
}
6364

@@ -140,6 +141,7 @@ StaticLayer::getParameters()
140141
// Enforce bounds
141142
lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
142143
map_received_ = false;
144+
update_in_progress_.store(false);
143145

144146
transform_tolerance_ = tf2::durationFromSec(temp_tf_tol);
145147
}
@@ -193,6 +195,9 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
193195

194196
unsigned int index = 0;
195197

198+
// we have a new map, update full size of map
199+
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
200+
196201
// initialize the costmap with static data
197202
for (unsigned int i = 0; i < size_y; ++i) {
198203
for (unsigned int j = 0; j < size_x; ++j) {
@@ -204,8 +209,6 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
204209

205210
map_frame_ = new_map.header.frame_id;
206211

207-
// we have a new map, update full size of map
208-
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
209212
x_ = y_ = 0;
210213
width_ = size_x_;
211214
height_ = size_y_;
@@ -249,9 +252,15 @@ void
249252
StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
250253
{
251254
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
252-
processMap(*new_map);
253255
if (!map_received_) {
254256
map_received_ = true;
257+
processMap(*new_map);
258+
}
259+
if (update_in_progress_.load()) {
260+
map_buffer_ = new_map;
261+
} else {
262+
processMap(*new_map);
263+
map_buffer_ = nullptr;
255264
}
256265
}
257266

@@ -311,6 +320,14 @@ StaticLayer::updateBounds(
311320
}
312321

313322
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
323+
update_in_progress_.store(true);
324+
325+
// If there is a new available map, load it.
326+
if (map_buffer_) {
327+
processMap(*map_buffer_);
328+
map_buffer_ = nullptr;
329+
}
330+
314331
if (!layered_costmap_->isRolling() ) {
315332
if (!(has_updated_data_ || has_extra_bounds_)) {
316333
return;
@@ -338,6 +355,7 @@ StaticLayer::updateCosts(
338355
int min_i, int min_j, int max_i, int max_j)
339356
{
340357
if (!enabled_) {
358+
update_in_progress_.store(false);
341359
return;
342360
}
343361
if (!map_received_) {
@@ -347,6 +365,7 @@ StaticLayer::updateCosts(
347365
RCLCPP_WARN(node_->get_logger(), "Can't update static costmap layer, no map received");
348366
count = 0;
349367
}
368+
update_in_progress_.store(false);
350369
return;
351370
}
352371

@@ -369,6 +388,7 @@ StaticLayer::updateCosts(
369388
transform_tolerance_);
370389
} catch (tf2::TransformException & ex) {
371390
RCLCPP_ERROR(node_->get_logger(), "StaticLayer: %s", ex.what());
391+
update_in_progress_.store(false);
372392
return;
373393
}
374394
// Copy map data given proper transformations
@@ -393,6 +413,7 @@ StaticLayer::updateCosts(
393413
}
394414
}
395415
}
416+
update_in_progress_.store(false);
396417
}
397418

398419
} // namespace nav2_costmap_2d

0 commit comments

Comments
 (0)