Overview

The clear_costmap_recovery::ClearCostmapRecovery is a simple recovery behavior that clears out space in the navigation stack's costmaps by reverting to the static map outside of a given radius away from the robot. It adheres to the nav_core::RecoveryBehavior interface found in the nav_core package and can be used as a recovery behavior plugin for the move_base node.

ClearCostmapRecovery

The clear_costmap_recovery::ClearCostmapRecovery object exposes its functionality as a C++ ROS Wrapper. It operates within a ROS namespace (assumed to be name from here on) specified on initialization. It adheres to the nav_core::RecoveryBehavior interface found in the nav_core package.

Example creation of a clear_costmap_recovery::ClearCostmapRecovery object:

   1 #include <tf/transform_listener.h>
   2 #include <costmap_2d/costmap_2d_ros.h>
   3 #include <clear_costmap_recovery/clear_costmap_recovery.h>
   4 
   5 ...
   6 tf::TransformListener tf(ros::Duration(10));
   7 costmap_2d::Costmap2DROS global_costmap("global_costmap", tf);
   8 costmap_2d::Costmap2DROS local_costmap("local_costmap", tf);
   9 
  10 clear_costmap_recovery::ClearCostmapRecovery ccr;
  11 ccr.initialize("my_clear_costmap_recovery", &tf, &global_costmap, &local_costmap);
  12 
  13 ccr.runBehavior();

API Stability

  • The C++ API is stable.
  • The ROS API is stable.

ROS Parameters

~<name>/reset_distance (double, default: 3.0)

  • The length of the side of a square centered on the robot pose, outside which obstacles will be removed from the costmaps when they are reverted to the static map.
~<name>/invert_area_to_clear (bool, default: false)
  • Clears costmap/s outside of a square centered on the robot pose, if false and inside, if true. The length of the side of the square is set by '~<name>/reset_distance' parameter.
~<name>/layer_names (list, default: ["obstacles"])
  • Clears only the 'layers' that are mentioned in the 'layer_names' parameter. The layers are defined according to the plugins for local_costmap and global_costmap.

C++ API

The C++ clear_costmap_recovery::ClearCostmapRecovery class adheres to the nav_core::RecoveryBehavior interface found in the nav_core package. For detailed documentation, please see ClearCostmapRecovery Documentation.

Wiki: clear_costmap_recovery (last edited 2023-11-29 04:29:40 by AkashKC)