navigation: amcl | base_local_planner | carrot_planner | clear_costmap_recovery | costmap_2d | dwa_local_planner | fake_localization | map_server | move_base | move_base_msgs | move_slow_and_clear | nav_core | navfn | robot_pose_ekf | rotate_recovery | voxel_grid
Package Summary
This package provides a recovery behavior for the navigation stack that attempts to clear space by reverting the costmaps used by the navigation stack to the static map outside of a given area.
- Author: Eitan Marder-Eppstein
- License: BSD
- Repository: wg-kforge
- Source: hg https://kforge.ros.org/navigation/navigation
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("gloabl_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();
14
API Stability
- The C++ API is stable.
- The ROS API is stable.
ROS Parameters
~<name>/reset_distance (double, default: 3.0)
- The radius away from the robot in meters outside which obstacles will be removed from the costmaps when they are reverted to the static map.
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.






