@@ -138,6 +138,7 @@ StaticLayer::getParameters()
138
138
declareParameter (" transform_tolerance" , rclcpp::ParameterValue (0.0 ));
139
139
declareParameter (" map_topic" , rclcpp::ParameterValue (" map" ));
140
140
declareParameter (" footprint_clearing_enabled" , rclcpp::ParameterValue (false ));
141
+ declareParameter (" restore_outdated_footprint" , rclcpp::ParameterValue (false ));
141
142
142
143
auto node = node_.lock ();
143
144
if (!node) {
@@ -147,6 +148,7 @@ StaticLayer::getParameters()
147
148
node->get_parameter (name_ + " ." + " enabled" , enabled_);
148
149
node->get_parameter (name_ + " ." + " subscribe_to_updates" , subscribe_to_updates_);
149
150
node->get_parameter (name_ + " ." + " footprint_clearing_enabled" , footprint_clearing_enabled_);
151
+ node->get_parameter (name_ + " ." + " restore_outdated_footprint" , restore_outdated_footprint_);
150
152
node->get_parameter (name_ + " ." + " map_topic" , map_topic_);
151
153
map_topic_ = joinWithParentNamespace (map_topic_);
152
154
node->get_parameter (
@@ -322,6 +324,46 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u
322
324
has_updated_data_ = true ;
323
325
}
324
326
327
+ void
328
+ StaticLayer::getCellsOccupiedByFootprint (
329
+ std::vector<MapLocation> & cells_occupied_by_footprint,
330
+ const std::vector<geometry_msgs::msg::Point > & footprint)
331
+ {
332
+ // we assume the polygon is given in the global_frame...
333
+ // we need to transform it to map coordinates
334
+ std::vector<MapLocation> map_polygon;
335
+ for (const auto & point : footprint) {
336
+ MapLocation loc;
337
+ if (!this ->worldToMap (point.x , point.y , loc.x , loc.y )) {
338
+ // ("Polygon lies outside map bounds, so we can't fill it");
339
+ return ;
340
+ }
341
+ map_polygon.push_back (loc);
342
+ }
343
+
344
+ // get the cells that fill the polygon
345
+ this ->convexFillCells (map_polygon, cells_occupied_by_footprint);
346
+ }
347
+
348
+ void StaticLayer::resetCells (
349
+ const std::vector<MapLocation> & resetting_cells, unsigned char cost)
350
+ {
351
+
352
+ for (const auto & cell : resetting_cells) {
353
+ setCost (cell.x , cell.y , cost);
354
+ }
355
+ }
356
+
357
+ void StaticLayer::restoreCellsFromMap (
358
+ const std::vector<MapLocation> & restoring_cells,
359
+ const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer)
360
+ {
361
+
362
+ for (const auto & cell : restoring_cells) {
363
+ unsigned int index = getIndex (cell.x , cell.y );
364
+ costmap_[index ] = interpretValue (map_buffer->data [index ]);
365
+ }
366
+ }
325
367
326
368
void
327
369
StaticLayer::updateBounds (
@@ -374,10 +416,17 @@ StaticLayer::updateFootprint(
374
416
{
375
417
if (!footprint_clearing_enabled_) {return ;}
376
418
419
+ if (restore_outdated_footprint_) {
420
+ // Increase the bounds to make the outdated footprint restored by layered costmap
421
+ for (const auto & point : transformed_footprint_) {
422
+ touch (point.x , point.y , min_x, min_y, max_x, max_y);
423
+ }
424
+ }
425
+
377
426
transformFootprint (robot_x, robot_y, robot_yaw, getFootprint (), transformed_footprint_);
378
427
379
- for (unsigned int i = 0 ; i < transformed_footprint_. size (); i++ ) {
380
- touch (transformed_footprint_[i] .x , transformed_footprint_[i] .y , min_x, min_y, max_x, max_y);
428
+ for (const auto & point : transformed_footprint_) {
429
+ touch (point .x , point .y , min_x, min_y, max_x, max_y);
381
430
}
382
431
}
383
432
@@ -400,6 +449,17 @@ StaticLayer::updateCosts(
400
449
return ;
401
450
}
402
451
452
+ if (footprint_clearing_enabled_) {
453
+ if (restore_outdated_footprint_) {
454
+ restoreCellsFromMap (cells_cleared_by_footprint_, map_buffer_);
455
+ }
456
+
457
+ cells_cleared_by_footprint_.clear ();
458
+ getCellsOccupiedByFootprint (cells_cleared_by_footprint_, transformed_footprint_);
459
+
460
+ resetCells (cells_cleared_by_footprint_, nav2_costmap_2d::FREE_SPACE);
461
+ }
462
+
403
463
if (!layered_costmap_->isRolling ()) {
404
464
// if not rolling, the layered costmap (master_grid) has same coordinates as this layer
405
465
if (!use_maximum_) {
@@ -444,16 +504,6 @@ StaticLayer::updateCosts(
444
504
}
445
505
}
446
506
447
- if (footprint_clearing_enabled_) {
448
- for (const auto index : cleared_indexes_in_map_) {
449
- master_grid.setCost (index , interpretValue (map_buffer_->data [index ]));
450
- }
451
- cleared_indexes_in_map_.clear ();
452
- master_grid.setConvexPolygonCost (transformed_footprint_, [this ](unsigned int index ) {
453
- cleared_indexes_in_map_.push_back (index );
454
- return nav2_costmap_2d::FREE_SPACE;
455
- });
456
- }
457
507
current_ = true ;
458
508
}
459
509
@@ -496,6 +546,8 @@ StaticLayer::dynamicParametersCallback(
496
546
} else if (param_type == ParameterType::PARAMETER_BOOL) {
497
547
if (param_name == name_ + " ." + " footprint_clearing_enabled" ) {
498
548
footprint_clearing_enabled_ = parameter.as_bool ();
549
+ } else if (param_name == name_ + " ." + " restore_outdated_footprint" ) {
550
+ restore_outdated_footprint_ = parameter.as_bool ();
499
551
}
500
552
}
501
553
}
0 commit comments