Public Member Functions | Private Attributes
rotate_recovery::RotateRecovery Class Reference

A recovery behavior that rotates the robot in-place to attempt to clear out space. More...

#include <rotate_recovery.h>

Inheritance diagram for rotate_recovery::RotateRecovery:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
 Initialization function for the RotateRecovery recovery behavior.
 RotateRecovery ()
 Constructor, make sure to call initialize in addition to actually initialize the object.
void runBehavior ()
 Run the RotateRecovery recovery behavior.
 ~RotateRecovery ()
 Destructor for the rotate recovery behavior.

Private Attributes

double acc_lim_th_
costmap_2d::Costmap2D costmap_
double frequency_
costmap_2d::Costmap2DROSglobal_costmap_
bool initialized_
costmap_2d::Costmap2DROSlocal_costmap_
double max_rotational_vel_
double min_rotational_vel_
std::string name_
double sim_granularity_
tf::TransformListenertf_
double tolerance_
base_local_planner::CostmapModelworld_model_

Detailed Description

A recovery behavior that rotates the robot in-place to attempt to clear out space.

Definition at line 53 of file rotate_recovery.h.


Constructor & Destructor Documentation

Constructor, make sure to call initialize in addition to actually initialize the object.

Parameters:
@return

Definition at line 44 of file rotate_recovery.cpp.

Destructor for the rotate recovery behavior.

Definition at line 77 of file rotate_recovery.cpp.


Member Function Documentation

void rotate_recovery::RotateRecovery::initialize ( std::string  name,
tf::TransformListener tf,
costmap_2d::Costmap2DROS global_costmap,
costmap_2d::Costmap2DROS local_costmap 
) [virtual]

Initialization function for the RotateRecovery recovery behavior.

Parameters:
tfA pointer to a transform listener
global_costmapA pointer to the global_costmap used by the navigation stack
local_costmapA pointer to the local_costmap used by the navigation stack

Implements nav_core::RecoveryBehavior.

Definition at line 47 of file rotate_recovery.cpp.

Run the RotateRecovery recovery behavior.

Implements nav_core::RecoveryBehavior.

Definition at line 81 of file rotate_recovery.cpp.


Member Data Documentation

Definition at line 87 of file rotate_recovery.h.

Definition at line 83 of file rotate_recovery.h.

Definition at line 87 of file rotate_recovery.h.

Definition at line 82 of file rotate_recovery.h.

Definition at line 86 of file rotate_recovery.h.

Definition at line 82 of file rotate_recovery.h.

Definition at line 87 of file rotate_recovery.h.

Definition at line 87 of file rotate_recovery.h.

Definition at line 84 of file rotate_recovery.h.

Definition at line 87 of file rotate_recovery.h.

Definition at line 85 of file rotate_recovery.h.

Definition at line 87 of file rotate_recovery.h.

Definition at line 88 of file rotate_recovery.h.


The documentation for this class was generated from the following files:


rotate_recovery
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:07:21