Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,6 @@ class InflationLayer : public Layer

virtual void reset()
{
undeclareAllParameters();
onInitialize();
}

Expand Down
1 change: 0 additions & 1 deletion nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -655,7 +655,6 @@ ObstacleLayer::reset()
resetMaps();
current_ = true;
activate();
undeclareAllParameters();
}

} // namespace nav2_costmap_2d
1 change: 0 additions & 1 deletion nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,6 @@ StaticLayer::reset()
map_sub_.reset();
map_update_sub_.reset();

undeclareAllParameters();
onInitialize();
}

Expand Down
1 change: 0 additions & 1 deletion nav2_costmap_2d/plugins/voxel_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,6 @@ void VoxelLayer::reset()
deactivate();
resetMaps();
activate();
undeclareAllParameters();
voxel_pub_->on_activate();
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");

resetLayers();
param_subscriber_.reset();
delete layered_costmap_;
layered_costmap_ = nullptr;

Expand Down
12 changes: 1 addition & 11 deletions nav2_costmap_2d/test/integration/obstacle_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -357,20 +357,10 @@ TEST_F(TestNode, testRepeatedResets) {
return plugin->hasParameter(layer_param);
}));

// Reset all layers. This will un-declare all params and might re-declare internal ones
// Reset all layers. Parameters should be declared if not declared, otherwise skipped.
// Should run without throwing exceptions
ASSERT_NO_THROW(
for_each(begin(*plugins), end(*plugins), [](const auto & plugin) {
plugin->reset();
}));

// Check for node-level param
ASSERT_TRUE(node_->has_parameter(node_dummy.first));

// Layer-level parameters shouldn't be found
ASSERT_TRUE(
none_of(begin(*plugins), end(*plugins), [&layer_dummy](const auto & plugin) {
string layer_param = layer_dummy.first + "_" + plugin->getName();
return plugin->hasParameter(layer_param);
}));
}