00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef SBPL_RECOVERY_SBPL_RECOVERY_H_
00038 #define SBPL_RECOVERY_SBPL_RECOVERY_H_
00039
00040 #include <ros/ros.h>
00041 #include <nav_core/recovery_behavior.h>
00042 #include <costmap_2d/costmap_2d_ros.h>
00043 #include <pose_follower/pose_follower.h>
00044 #include <sbpl_lattice_planner/sbpl_lattice_planner.h>
00045 #include <nav_msgs/Path.h>
00046 #include <boost/thread.hpp>
00047 #include <base_local_planner/goal_functions.h>
00048
00049 namespace sbpl_recovery
00050 {
00051 class SBPLRecovery : public nav_core::RecoveryBehavior
00052 {
00053 public:
00054 SBPLRecovery();
00055
00056
00057 void initialize (std::string n, tf::TransformListener* tf,
00058 costmap_2d::Costmap2DROS* global_costmap,
00059 costmap_2d::Costmap2DROS* local_costmap);
00060
00061
00062 void runBehavior();
00063
00064 private:
00065 void planCB(const nav_msgs::Path::ConstPtr& plan);
00066 double sqDistance(const geometry_msgs::PoseStamped& p1,
00067 const geometry_msgs::PoseStamped& p2);
00068 std::vector<geometry_msgs::PoseStamped> makePlan();
00069
00070 costmap_2d::Costmap2DROS* global_costmap_;
00071 costmap_2d::Costmap2DROS* local_costmap_;
00072 tf::TransformListener* tf_;
00073 sbpl_lattice_planner::SBPLLatticePlanner global_planner_;
00074 pose_follower::PoseFollower local_planner_;
00075 bool initialized_;
00076 ros::Subscriber plan_sub_;
00077 ros::Publisher vel_pub_;
00078 boost::mutex plan_mutex_;
00079 nav_msgs::Path plan_;
00080 double control_frequency_, sq_planning_distance_, controller_patience_;
00081 int planning_attempts_, attempts_per_run_;
00082 bool use_local_frame_;
00083 };
00084
00085 };
00086 #endif