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>

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::Costmap2DROS * global_costmap_
bool initialized_
costmap_2d::Costmap2DROS * local_costmap_
double max_rotational_vel_
double min_rotational_vel_
std::string name_
double sim_granularity_
tf::TransformListener * tf_
double tolerance_
base_local_planner::CostmapModel * world_model_

Detailed Description

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

Definition at line 52 of file rotate_recovery.h.


Constructor & Destructor Documentation

rotate_recovery::RotateRecovery::RotateRecovery (  ) 

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

Parameters:
@return 

Definition at line 40 of file rotate_recovery.cpp.

rotate_recovery::RotateRecovery::~RotateRecovery (  ) 

Destructor for the rotate recovery behavior.

Definition at line 74 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 
)

Initialization function for the RotateRecovery recovery behavior.

Parameters:
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

Definition at line 43 of file rotate_recovery.cpp.

void rotate_recovery::RotateRecovery::runBehavior (  ) 

Run the RotateRecovery recovery behavior.

Definition at line 78 of file rotate_recovery.cpp.


Member Data Documentation

Definition at line 86 of file rotate_recovery.h.

costmap_2d::Costmap2D rotate_recovery::RotateRecovery::costmap_ [private]

Definition at line 82 of file rotate_recovery.h.

Definition at line 86 of file rotate_recovery.h.

costmap_2d::Costmap2DROS* rotate_recovery::RotateRecovery::global_costmap_ [private]

Definition at line 81 of file rotate_recovery.h.

Definition at line 85 of file rotate_recovery.h.

costmap_2d::Costmap2DROS * rotate_recovery::RotateRecovery::local_costmap_ [private]

Definition at line 81 of file rotate_recovery.h.

Definition at line 86 of file rotate_recovery.h.

Definition at line 86 of file rotate_recovery.h.

Definition at line 83 of file rotate_recovery.h.

Definition at line 86 of file rotate_recovery.h.

tf::TransformListener* rotate_recovery::RotateRecovery::tf_ [private]

Definition at line 84 of file rotate_recovery.h.

Definition at line 86 of file rotate_recovery.h.

base_local_planner::CostmapModel* rotate_recovery::RotateRecovery::world_model_ [private]

Definition at line 87 of file rotate_recovery.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables


rotate_recovery
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Jan 11 09:33:10 2013