@@ -133,6 +133,7 @@ StaticLayer::getParameters()
133133 declareParameter (" map_subscribe_transient_local" , rclcpp::ParameterValue (true ));
134134 declareParameter (" transform_tolerance" , rclcpp::ParameterValue (0.0 ));
135135 declareParameter (" map_topic" , rclcpp::ParameterValue (" " ));
136+ declareParameter (" footprint_clearing_enabled" , rclcpp::ParameterValue (false ));
136137
137138 auto node = node_.lock ();
138139 if (!node) {
@@ -141,6 +142,7 @@ StaticLayer::getParameters()
141142
142143 node->get_parameter (name_ + " ." + " enabled" , enabled_);
143144 node->get_parameter (name_ + " ." + " subscribe_to_updates" , subscribe_to_updates_);
145+ node->get_parameter (name_ + " ." + " footprint_clearing_enabled" , footprint_clearing_enabled_);
144146 std::string private_map_topic, global_map_topic;
145147 node->get_parameter (name_ + " ." + " map_topic" , private_map_topic);
146148 node->get_parameter (" map_topic" , global_map_topic);
@@ -333,7 +335,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u
333335
334336void
335337StaticLayer::updateBounds (
336- 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,
337339 double * min_y,
338340 double * max_x,
339341 double * max_y)
@@ -371,6 +373,24 @@ StaticLayer::updateBounds(
371373 *max_y = std::max (wy, *max_y);
372374
373375 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+ }
374394}
375395
376396void
@@ -392,6 +412,10 @@ StaticLayer::updateCosts(
392412 return ;
393413 }
394414
415+ if (footprint_clearing_enabled_) {
416+ setConvexPolygonCost (transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
417+ }
418+
395419 if (!layered_costmap_->isRolling ()) {
396420 // if not rolling, the layered costmap (master_grid) has same coordinates as this layer
397421 if (!use_maximum_) {
@@ -474,6 +498,10 @@ StaticLayer::dynamicParametersCallback(
474498 has_updated_data_ = true ;
475499 current_ = false ;
476500 }
501+ } else if (param_type == ParameterType::PARAMETER_BOOL) {
502+ if (param_name == name_ + " ." + " footprint_clearing_enabled" ) {
503+ footprint_clearing_enabled_ = parameter.as_bool ();
504+ }
477505 }
478506 }
479507 result.successful = true ;
0 commit comments