A recovery behavior that reverts the navigation stack's costmaps to the static map outside of a user-specified region. More...
#include <clear_costmap_recovery.h>
Public Member Functions | |
ClearCostmapRecovery () | |
Constructor, make sure to call initialize in addition to actually initialize the object. More... | |
void | initialize (std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap) |
Initialization function for the ClearCostmapRecovery recovery behavior. More... | |
void | runBehavior () |
Run the ClearCostmapRecovery recovery behavior. Reverts the costmap to the static map outside of a user-specified window and clears unknown space around the robot. More... | |
Public Member Functions inherited from nav_core::RecoveryBehavior | |
virtual | ~RecoveryBehavior () |
Private Member Functions | |
void | clear (costmap_2d::Costmap2DROS *costmap) |
void | clearMap (boost::shared_ptr< costmap_2d::CostmapLayer > costmap, double pose_x, double pose_y) |
Private Attributes | |
std::string | affected_maps_ |
clear only local, global or both costmaps More... | |
std::set< std::string > | clearable_layers_ |
Layer names which will be cleared. More... | |
bool | force_updating_ |
force costmap update after clearing, so we don't need to wait for update thread More... | |
costmap_2d::Costmap2DROS * | global_costmap_ |
bool | initialized_ |
bool | invert_area_to_clear_ |
costmap_2d::Costmap2DROS * | local_costmap_ |
std::string | name_ |
double | reset_distance_ |
tf2_ros::Buffer * | tf_ |
Additional Inherited Members | |
Protected Member Functions inherited from nav_core::RecoveryBehavior | |
RecoveryBehavior () | |
A recovery behavior that reverts the navigation stack's costmaps to the static map outside of a user-specified region.
Definition at line 84 of file clear_costmap_recovery.h.
clear_costmap_recovery::ClearCostmapRecovery::ClearCostmapRecovery | ( | ) |
Constructor, make sure to call initialize in addition to actually initialize the object.
Definition at line 48 of file clear_costmap_recovery.cpp.
|
private |
Definition at line 131 of file clear_costmap_recovery.cpp.
|
private |
Definition at line 168 of file clear_costmap_recovery.cpp.
|
virtual |
Initialization function for the ClearCostmapRecovery recovery behavior.
tf | A pointer to a transform listener |
global_costmap | A pointer to the global_costmap used by the navigation stack |
local_costmap | A pointer to the local_costmap used by the navigation stack |
Implements nav_core::RecoveryBehavior.
Definition at line 51 of file clear_costmap_recovery.cpp.
|
virtual |
Run the ClearCostmapRecovery recovery behavior. Reverts the costmap to the static map outside of a user-specified window and clears unknown space around the robot.
Implements nav_core::RecoveryBehavior.
Definition at line 89 of file clear_costmap_recovery.cpp.
|
private |
clear only local, global or both costmaps
Definition at line 119 of file clear_costmap_recovery.h.
|
private |
Layer names which will be cleared.
Definition at line 120 of file clear_costmap_recovery.h.
|
private |
force costmap update after clearing, so we don't need to wait for update thread
Definition at line 116 of file clear_costmap_recovery.h.
|
private |
Definition at line 112 of file clear_costmap_recovery.h.
|
private |
Definition at line 115 of file clear_costmap_recovery.h.
|
private |
Definition at line 118 of file clear_costmap_recovery.h.
|
private |
Definition at line 112 of file clear_costmap_recovery.h.
|
private |
Definition at line 113 of file clear_costmap_recovery.h.
|
private |
Definition at line 117 of file clear_costmap_recovery.h.
|
private |
Definition at line 114 of file clear_costmap_recovery.h.