Skip to content

Commit

Permalink
removing clearable layer param (unused) (#4280)
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski authored Apr 28, 2024
1 parent 1f980a1 commit 9f6b0dd
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,6 @@ class ClearCostmapService

// Clearing parameters
unsigned char reset_value_;
std::vector<std::string> clearable_layers_;

// Server for clearing the costmap
rclcpp::Service<nav2_msgs::srv::ClearCostmapExceptRegion>::SharedPtr clear_except_service_;
Expand Down
2 changes: 0 additions & 2 deletions nav2_costmap_2d/src/clear_costmap_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,6 @@ ClearCostmapService::ClearCostmapService(
logger_ = node->get_logger();
reset_value_ = costmap_.getCostmap()->getDefaultValue();

node->get_parameter("clearable_layers", clearable_layers_);

clear_except_service_ = node->create_service<ClearExceptRegion>(
"clear_except_" + costmap_.getName(),
std::bind(
Expand Down
3 changes: 0 additions & 3 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,8 +109,6 @@ void Costmap2DROS::init()
{
RCLCPP_INFO(get_logger(), "Creating Costmap");

std::vector<std::string> clearable_layers{"obstacle_layer", "voxel_layer", "range_layer"};

declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
Expand All @@ -135,7 +133,6 @@ void Costmap2DROS::init()
declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
declare_parameter("use_maximum", rclcpp::ParameterValue(false));
declare_parameter("clearable_layers", rclcpp::ParameterValue(clearable_layers));
}

Costmap2DROS::~Costmap2DROS()
Expand Down

0 comments on commit 9f6b0dd

Please sign in to comment.