Skip to content

Commit af7e3ca

Browse files
semeyerzLeroyR
authored andcommitted
changed clearable_layers_default to obstacle_layer as this is the default used by move_base costmaps
1 parent 5f41333 commit af7e3ca

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

clear_costmap_recovery/src/clear_costmap_recovery.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ void ClearCostmapRecovery::initialize(std::string name, tf::TransformListener* t
6161
private_nh.param("reset_distance", reset_distance_, 3.0);
6262

6363
std::vector<std::string> clearable_layers_default, clearable_layers;
64-
clearable_layers_default.push_back( std::string("obstacles") );
64+
clearable_layers_default.push_back( std::string("obstacle_layer") );
6565
private_nh.param("layer_names", clearable_layers, clearable_layers_default);
6666

6767
for(unsigned i=0; i < clearable_layers.size(); i++) {

0 commit comments

Comments
 (0)