ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

The documentation for recovery behaviors is in the move_base wiki. Basically, you just list the plugins you want to use, and since you specifically mention clear_costmap_recovery, we'll go with that. I agree the clear_costmap_recovery documentation isn't the most informative, but you can get a look at the plugin's parameters by looking at the source code. This line indicates the most relevant parameter to your question, layer_names:

private_nh.param("layer_names", clearable_layers, clearable_layers_default);

This code is a plugin to move_base, so it's parameters are set through that node. Here's an example of how I might set this recovery behavior's parameters in move_base_params.yaml:

recovery_behaviors:
  - name: costmap_reset
    type: clear_costmap_recovery/ClearCostmapRecovery

costmap_reset:
  reset_distance: 0.0
  layer_names: ["my_layer"]

I set the recovery_behaviors parameter of the move_base node to a single-item list (sequence), where the item is indicated by the dash. Note that in the move_base wiki, it shows the default value as an bracketed list (flow style); this is simply a different syntax for the same type of YAML collection. I name the the specific recovery behavior "costmap_reset," and indicate its type. To change its parameters, I define them under its namespace (same as the behavior name) on the same level as recover_behaviors. I tell the plugin to only clear my_layer by giving the layer_names parameter single-item sequence of strings. The actual definition of my_layer is something that happens in the costmap configuration files (see the question you linked), but you can reference those layers here since the move_base node handles all of it.

If you've tried this, and it's not working, please clarify what happens (errors, warnings, behavior, etc.) and post your own files and output for troubleshooting.

The documentation for recovery behaviors is in the move_base wiki. Basically, you just list the plugins you want to use, and since you specifically mention clear_costmap_recovery, we'll go with that. I agree the clear_costmap_recovery documentation isn't the most informative, but you can get a look at the plugin's parameters by looking at the source code. This line indicates the most relevant parameter to your question, layer_names:

private_nh.param("layer_names", clearable_layers, clearable_layers_default);

This code is a plugin to move_base, so it's parameters are set through that node. Here's an example of how I might set this recovery behavior's parameters in move_base_params.yaml:

recovery_behaviors:
  - name: costmap_reset
    type: clear_costmap_recovery/ClearCostmapRecovery

costmap_reset:
  reset_distance: 0.0
  layer_names: ["my_layer"]

I set the recovery_behaviors parameter of the move_base node to a single-item list (sequence), where the item is indicated by the dash. Note that in the move_base wiki, it shows the default value as an bracketed list (flow style); this is simply a different syntax for the same type of YAML collection. I name the the specific recovery behavior "costmap_reset," and indicate its type. To change its parameters, I define them under its namespace (same as the behavior name) on the same level as recover_behaviors. I tell the plugin to only clear my_layer by giving the layer_names parameter single-item sequence of strings. The actual definition of my_layer is something that happens in the costmap configuration files (see the question you linked), but you can reference those layers here since the move_base node handles all of it.

If you've tried this, and it's not working, please clarify what happens (errors, warnings, behavior, etc.) and post your own files and output for troubleshooting.


Update

i am not sure if it makes a difference when its triggered via rosservice call or move_base directly

The clear_costmaps service and recovery behavior are separate. The service resets all layers and doesn't take parameters, so that's not something you can change without modifying the source code:

bool MoveBase::clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp){
  //clear the costmaps
  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_controller(*(controller_costmap_ros_->getCostmap()->getMutex()));
  controller_costmap_ros_->resetLayers();

  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock_planner(*(planner_costmap_ros_->getCostmap()->getMutex()));
  planner_costmap_ros_->resetLayers();
  return true;
}

The service simply calls resetLayers() for both the local (controller_costmap_ros_) and global (planner_costmap_ros_) costmaps.