37 #ifndef SBPL_RECOVERY_SBPL_RECOVERY_H_ 38 #define SBPL_RECOVERY_SBPL_RECOVERY_H_ 45 #include <geometry_msgs/PoseStamped.h> 46 #include <nav_msgs/Path.h> 47 #include <boost/thread.hpp> 66 void planCB(
const nav_msgs::Path::ConstPtr& plan);
67 double sqDistance(
const geometry_msgs::PoseStamped& p1,
68 const geometry_msgs::PoseStamped& p2);
69 std::vector<geometry_msgs::PoseStamped>
makePlan();
ros::Subscriber plan_sub_
costmap_2d::Costmap2DROS * local_costmap_
sbpl_lattice_planner::SBPLLatticePlanner global_planner_
tf::TransformListener * tf_
costmap_2d::Costmap2DROS * global_costmap_
pose_follower::PoseFollower local_planner_
double control_frequency_
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
double controller_patience_
std::vector< geometry_msgs::PoseStamped > makePlan()
double sqDistance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
double sq_planning_distance_
void planCB(const nav_msgs::Path::ConstPtr &plan)