45
45
#include " pluginlib/class_list_macros.hpp"
46
46
#include " tf2/convert.h"
47
47
#include " tf2_geometry_msgs/tf2_geometry_msgs.hpp"
48
+ #include " nav2_util/validate_messages.hpp"
48
49
49
50
PLUGINLIB_EXPORT_CLASS (nav2_costmap_2d::StaticLayer, nav2_costmap_2d::Layer)
50
51
@@ -132,6 +133,7 @@ StaticLayer::getParameters()
132
133
declareParameter (" map_subscribe_transient_local" , rclcpp::ParameterValue (true ));
133
134
declareParameter (" transform_tolerance" , rclcpp::ParameterValue (0.0 ));
134
135
declareParameter (" map_topic" , rclcpp::ParameterValue (" " ));
136
+ declareParameter (" footprint_clearing_enabled" , rclcpp::ParameterValue (false ));
135
137
136
138
auto node = node_.lock ();
137
139
if (!node) {
@@ -140,6 +142,7 @@ StaticLayer::getParameters()
140
142
141
143
node->get_parameter (name_ + " ." + " enabled" , enabled_);
142
144
node->get_parameter (name_ + " ." + " subscribe_to_updates" , subscribe_to_updates_);
145
+ node->get_parameter (name_ + " ." + " footprint_clearing_enabled" , footprint_clearing_enabled_);
143
146
std::string private_map_topic, global_map_topic;
144
147
node->get_parameter (name_ + " ." + " map_topic" , private_map_topic);
145
148
node->get_parameter (" map_topic" , global_map_topic);
@@ -277,6 +280,10 @@ StaticLayer::interpretValue(unsigned char value)
277
280
void
278
281
StaticLayer::incomingMap (const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
279
282
{
283
+ if (!nav2_util::validateMsg (*new_map)) {
284
+ RCLCPP_ERROR (logger_, " Received map message is malformed. Rejecting." );
285
+ return ;
286
+ }
280
287
if (!map_received_) {
281
288
processMap (*new_map);
282
289
map_received_ = true ;
@@ -328,7 +335,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u
328
335
329
336
void
330
337
StaticLayer::updateBounds (
331
- double /* robot_x*/ , double /* robot_y*/ , double /* robot_yaw*/ , double * min_x,
338
+ double robot_x, double robot_y, double robot_yaw, double * min_x,
332
339
double * min_y,
333
340
double * max_x,
334
341
double * max_y)
@@ -366,6 +373,24 @@ StaticLayer::updateBounds(
366
373
*max_y = std::max (wy, *max_y);
367
374
368
375
has_updated_data_ = false ;
376
+
377
+ updateFootprint (robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
378
+ }
379
+
380
+ void
381
+ StaticLayer::updateFootprint (
382
+ double robot_x, double robot_y, double robot_yaw,
383
+ double * min_x, double * min_y,
384
+ double * max_x,
385
+ double * max_y)
386
+ {
387
+ if (!footprint_clearing_enabled_) {return ;}
388
+
389
+ transformFootprint (robot_x, robot_y, robot_yaw, getFootprint (), transformed_footprint_);
390
+
391
+ for (unsigned int i = 0 ; i < transformed_footprint_.size (); i++) {
392
+ touch (transformed_footprint_[i].x , transformed_footprint_[i].y , min_x, min_y, max_x, max_y);
393
+ }
369
394
}
370
395
371
396
void
@@ -387,6 +412,10 @@ StaticLayer::updateCosts(
387
412
return ;
388
413
}
389
414
415
+ if (footprint_clearing_enabled_) {
416
+ setConvexPolygonCost (transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
417
+ }
418
+
390
419
if (!layered_costmap_->isRolling ()) {
391
420
// if not rolling, the layered costmap (master_grid) has same coordinates as this layer
392
421
if (!use_maximum_) {
@@ -469,6 +498,10 @@ StaticLayer::dynamicParametersCallback(
469
498
has_updated_data_ = true ;
470
499
current_ = false ;
471
500
}
501
+ } else if (param_type == ParameterType::PARAMETER_BOOL) {
502
+ if (param_name == name_ + " ." + " footprint_clearing_enabled" ) {
503
+ footprint_clearing_enabled_ = parameter.as_bool ();
504
+ }
472
505
}
473
506
}
474
507
result.successful = true ;
0 commit comments