sbpl_recovery::SBPLRecovery Class Reference

#include <sbpl_recovery.h>

List of all members.

Public Member Functions

void initialize (std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
void runBehavior ()
 SBPLRecovery ()

Private Member Functions

std::vector
< geometry_msgs::PoseStamped > 
makePlan ()
void planCB (const nav_msgs::Path::ConstPtr &plan)
double sqDistance (const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)

Private Attributes

int attempts_per_run_
double control_frequency_
double controller_patience_
costmap_2d::Costmap2DROS * global_costmap_
sbpl_lattice_planner::SBPLLatticePlanner global_planner_
bool initialized_
costmap_2d::Costmap2DROS * local_costmap_
pose_follower::PoseFollower local_planner_
nav_msgs::Path plan_
boost::mutex plan_mutex_
ros::Subscriber plan_sub_
int planning_attempts_
double sq_planning_distance_
tf::TransformListener * tf_
bool use_local_frame_
ros::Publisher vel_pub_

Detailed Description

Definition at line 49 of file sbpl_recovery.h.


Constructor & Destructor Documentation

sbpl_recovery::SBPLRecovery::SBPLRecovery (  ) 

Member Function Documentation

void sbpl_recovery::SBPLRecovery::initialize ( std::string  n,
tf::TransformListener *  tf,
costmap_2d::Costmap2DROS *  global_costmap,
costmap_2d::Costmap2DROS *  local_costmap 
)
std::vector<geometry_msgs::PoseStamped> sbpl_recovery::SBPLRecovery::makePlan (  )  [private]
void sbpl_recovery::SBPLRecovery::planCB ( const nav_msgs::Path::ConstPtr &  plan  )  [private]
void sbpl_recovery::SBPLRecovery::runBehavior (  ) 
double sbpl_recovery::SBPLRecovery::sqDistance ( const geometry_msgs::PoseStamped &  p1,
const geometry_msgs::PoseStamped &  p2 
) [private]

Member Data Documentation

Definition at line 77 of file sbpl_recovery.h.

Definition at line 76 of file sbpl_recovery.h.

Definition at line 76 of file sbpl_recovery.h.

costmap_2d::Costmap2DROS* sbpl_recovery::SBPLRecovery::global_costmap_ [private]

Definition at line 66 of file sbpl_recovery.h.

sbpl_lattice_planner::SBPLLatticePlanner sbpl_recovery::SBPLRecovery::global_planner_ [private]

Definition at line 69 of file sbpl_recovery.h.

Definition at line 71 of file sbpl_recovery.h.

costmap_2d::Costmap2DROS* sbpl_recovery::SBPLRecovery::local_costmap_ [private]

Definition at line 67 of file sbpl_recovery.h.

pose_follower::PoseFollower sbpl_recovery::SBPLRecovery::local_planner_ [private]

Definition at line 70 of file sbpl_recovery.h.

nav_msgs::Path sbpl_recovery::SBPLRecovery::plan_ [private]

Definition at line 75 of file sbpl_recovery.h.

Definition at line 74 of file sbpl_recovery.h.

ros::Subscriber sbpl_recovery::SBPLRecovery::plan_sub_ [private]

Definition at line 72 of file sbpl_recovery.h.

Definition at line 77 of file sbpl_recovery.h.

Definition at line 76 of file sbpl_recovery.h.

tf::TransformListener* sbpl_recovery::SBPLRecovery::tf_ [private]

Definition at line 68 of file sbpl_recovery.h.

Definition at line 78 of file sbpl_recovery.h.

ros::Publisher sbpl_recovery::SBPLRecovery::vel_pub_ [private]

Definition at line 73 of file sbpl_recovery.h.


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


sbpl_recovery
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Jan 11 09:57:43 2013