@@ -58,6 +58,7 @@ namespace nav2_costmap_2d
58
58
{
59
59
60
60
StaticLayer::StaticLayer ()
61
+ : map_buffer_(nullptr )
61
62
{
62
63
}
63
64
@@ -140,6 +141,7 @@ StaticLayer::getParameters()
140
141
// Enforce bounds
141
142
lethal_threshold_ = std::max (std::min (temp_lethal_threshold, 100 ), 0 );
142
143
map_received_ = false ;
144
+ update_in_progress_.store (false );
143
145
144
146
transform_tolerance_ = tf2::durationFromSec (temp_tf_tol);
145
147
}
@@ -193,6 +195,9 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
193
195
194
196
unsigned int index = 0 ;
195
197
198
+ // we have a new map, update full size of map
199
+ std::lock_guard<Costmap2D::mutex_t > guard (*getMutex ());
200
+
196
201
// initialize the costmap with static data
197
202
for (unsigned int i = 0 ; i < size_y; ++i) {
198
203
for (unsigned int j = 0 ; j < size_x; ++j) {
@@ -204,8 +209,6 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map)
204
209
205
210
map_frame_ = new_map.header .frame_id ;
206
211
207
- // we have a new map, update full size of map
208
- std::lock_guard<Costmap2D::mutex_t > guard (*getMutex ());
209
212
x_ = y_ = 0 ;
210
213
width_ = size_x_;
211
214
height_ = size_y_;
@@ -249,9 +252,15 @@ void
249
252
StaticLayer::incomingMap (const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
250
253
{
251
254
std::lock_guard<Costmap2D::mutex_t > guard (*getMutex ());
252
- processMap (*new_map);
253
255
if (!map_received_) {
254
256
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 ;
255
264
}
256
265
}
257
266
@@ -311,6 +320,14 @@ StaticLayer::updateBounds(
311
320
}
312
321
313
322
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
+
314
331
if (!layered_costmap_->isRolling () ) {
315
332
if (!(has_updated_data_ || has_extra_bounds_)) {
316
333
return ;
@@ -338,6 +355,7 @@ StaticLayer::updateCosts(
338
355
int min_i, int min_j, int max_i, int max_j)
339
356
{
340
357
if (!enabled_) {
358
+ update_in_progress_.store (false );
341
359
return ;
342
360
}
343
361
if (!map_received_) {
@@ -347,6 +365,7 @@ StaticLayer::updateCosts(
347
365
RCLCPP_WARN (node_->get_logger (), " Can't update static costmap layer, no map received" );
348
366
count = 0 ;
349
367
}
368
+ update_in_progress_.store (false );
350
369
return ;
351
370
}
352
371
@@ -369,6 +388,7 @@ StaticLayer::updateCosts(
369
388
transform_tolerance_);
370
389
} catch (tf2::TransformException & ex) {
371
390
RCLCPP_ERROR (node_->get_logger (), " StaticLayer: %s" , ex.what ());
391
+ update_in_progress_.store (false );
372
392
return ;
373
393
}
374
394
// Copy map data given proper transformations
@@ -393,6 +413,7 @@ StaticLayer::updateCosts(
393
413
}
394
414
}
395
415
}
416
+ update_in_progress_.store (false );
396
417
}
397
418
398
419
} // namespace nav2_costmap_2d
0 commit comments