A recovery behavior that rotates the robot in-place to attempt to clear out space. More...
#include <rotate_recovery.h>

Public Member Functions | |
| void | initialize (std::string name, tf2_ros::Buffer *, costmap_2d::Costmap2DROS *, costmap_2d::Costmap2DROS *local_costmap) |
| Initialization function for the RotateRecovery recovery behavior. More... | |
| RotateRecovery () | |
| Constructor, make sure to call initialize in addition to actually initialize the object. More... | |
| void | runBehavior () |
| Run the RotateRecovery recovery behavior. More... | |
| ~RotateRecovery () | |
| Destructor for the rotate recovery behavior. More... | |
Public Member Functions inherited from nav_core::RecoveryBehavior | |
| virtual | ~RecoveryBehavior () |
Private Attributes | |
| double | acc_lim_th_ |
| double | frequency_ |
| bool | initialized_ |
| costmap_2d::Costmap2DROS * | local_costmap_ |
| double | max_rotational_vel_ |
| double | min_rotational_vel_ |
| double | sim_granularity_ |
| double | tolerance_ |
| base_local_planner::CostmapModel * | world_model_ |
Additional Inherited Members | |
Protected Member Functions inherited from nav_core::RecoveryBehavior | |
| RecoveryBehavior () | |
A recovery behavior that rotates the robot in-place to attempt to clear out space.
Definition at line 86 of file rotate_recovery.h.
| rotate_recovery::RotateRecovery::RotateRecovery | ( | ) |
Constructor, make sure to call initialize in addition to actually initialize the object.
Definition at line 89 of file rotate_recovery.cpp.
| rotate_recovery::RotateRecovery::~RotateRecovery | ( | ) |
Destructor for the rotate recovery behavior.
Definition at line 123 of file rotate_recovery.cpp.
|
virtual |
Initialization function for the RotateRecovery recovery behavior.
| name | Namespace used in initialization |
| tf | (unused) |
| global_costmap | (unused) |
| local_costmap | A pointer to the local_costmap used by the navigation stack |
Implements nav_core::RecoveryBehavior.
Definition at line 93 of file rotate_recovery.cpp.
|
virtual |
Run the RotateRecovery recovery behavior.
Implements nav_core::RecoveryBehavior.
Definition at line 128 of file rotate_recovery.cpp.
|
private |
Definition at line 117 of file rotate_recovery.h.
|
private |
Definition at line 117 of file rotate_recovery.h.
|
private |
Definition at line 116 of file rotate_recovery.h.
|
private |
Definition at line 115 of file rotate_recovery.h.
|
private |
Definition at line 117 of file rotate_recovery.h.
|
private |
Definition at line 117 of file rotate_recovery.h.
|
private |
Definition at line 117 of file rotate_recovery.h.
|
private |
Definition at line 117 of file rotate_recovery.h.
|
private |
Definition at line 118 of file rotate_recovery.h.