Go to the documentation of this file.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 DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_
00038 #define DWA_LOCAL_PLANNER_DWA_PLANNER_ROS_H_
00039 #include <angles/angles.h>
00040 #include <dwa_local_planner/dwa_planner.h>
00041 #include <boost/shared_ptr.hpp>
00042 #include <nav_core/base_local_planner.h>
00043
00044 namespace dwa_local_planner {
00049 class DWAPlannerROS : public nav_core::BaseLocalPlanner {
00050 public:
00054 DWAPlannerROS() : costmap_ros_(NULL), tf_(NULL), initialized_(false) {}
00055
00062 void initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros);
00063
00068 bool isGoalReached();
00069
00075 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
00076
00082 bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel);
00083
00084 private:
00085 inline double sign(double x){
00086 return x < 0.0 ? -1.0 : 1.0;
00087 }
00088
00097 bool rotateToGoal(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel);
00105 bool stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, geometry_msgs::Twist& cmd_vel);
00106
00111 void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);
00112
00113 costmap_2d::Costmap2DROS* costmap_ros_;
00114 tf::TransformListener* tf_;
00115 double max_vel_th_, min_vel_th_, min_rot_vel_;
00116 double rot_stopped_vel_, trans_stopped_vel_;
00117 double yaw_goal_tolerance_, xy_goal_tolerance_;
00118 bool prune_plan_;
00119 bool initialized_;
00120 ros::Subscriber odom_sub_;
00121 ros::Publisher g_plan_pub_, l_plan_pub_;
00122 boost::mutex odom_mutex_;
00123 nav_msgs::Odometry base_odom_;
00124 boost::shared_ptr<DWAPlanner> dp_;
00125 std::vector<geometry_msgs::PoseStamped> global_plan_;
00126 bool rotating_to_goal_;
00127 bool latch_xy_goal_tolerance_, xy_tolerance_latch_;
00128 };
00129 };
00130 #endif