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 NAV_MOVE_BASE_ACTION_H_
00038 #define NAV_MOVE_BASE_ACTION_H_
00039 #include <cmath>
00040 #include <ros/ros.h>
00041
00042 #include <actionlib/server/simple_action_server.h>
00043 #include <move_base_msgs/MoveBaseAction.h>
00044
00045 #include <nav_core/base_local_planner.h>
00046 #include <nav_core/base_global_planner.h>
00047 #include <nav_core/recovery_behavior.h>
00048 #include <geometry_msgs/PoseStamped.h>
00049 #include <costmap_2d/costmap_2d_ros.h>
00050 #include <costmap_2d/costmap_2d.h>
00051 #include <vector>
00052 #include <string>
00053 #include <nav_msgs/GetPlan.h>
00054 #include <geometry_msgs/Twist.h>
00055
00056 #include <pluginlib/class_loader.h>
00057 #include <std_srvs/Empty.h>
00058
00059 namespace move_base {
00060
00061 typedef actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> MoveBaseActionServer;
00062
00063 enum MoveBaseState {
00064 PLANNING,
00065 CONTROLLING,
00066 CLEARING
00067 };
00068
00069 enum RecoveryTrigger
00070 {
00071 PLANNING_R,
00072 CONTROLLING_R,
00073 OSCILLATION_R
00074 };
00075
00080 class MoveBase {
00081 public:
00087 MoveBase(std::string name, tf::TransformListener& tf);
00088
00092 virtual ~MoveBase();
00093
00100 bool executeCycle(geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& global_plan);
00101
00102 private:
00109 bool clearUnknownService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
00110
00111 private:
00118 bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
00119
00126 bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
00127
00134 bool makePlan(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
00135
00141 bool loadRecoveryBehaviors(ros::NodeHandle node);
00142
00146 void loadDefaultRecoveryBehaviors();
00147
00153 void clearCostmapWindows(double size_x, double size_y);
00154
00158 void publishZeroVelocity();
00159
00163 void resetState();
00164
00165 void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal);
00166
00167 void executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal);
00168
00169 bool isQuaternionValid(const geometry_msgs::Quaternion& q);
00170
00171 double distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2);
00172
00173 geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg);
00174
00175 tf::TransformListener& tf_;
00176
00177 MoveBaseActionServer* as_;
00178
00179 nav_core::BaseLocalPlanner* tc_;
00180 costmap_2d::Costmap2DROS* planner_costmap_ros_, *controller_costmap_ros_;
00181
00182 nav_core::BaseGlobalPlanner* planner_;
00183 std::string robot_base_frame_, global_frame_;
00184
00185 std::vector<boost::shared_ptr<nav_core::RecoveryBehavior> > recovery_behaviors_;
00186 unsigned int recovery_index_;
00187
00188 tf::Stamped<tf::Pose> global_pose_;
00189 double controller_frequency_, inscribed_radius_, circumscribed_radius_;
00190 double planner_patience_, controller_patience_;
00191 double conservative_reset_dist_, clearing_radius_;
00192 ros::Publisher current_goal_pub_, vel_pub_, action_goal_pub_;
00193 ros::Subscriber goal_sub_;
00194 ros::ServiceServer make_plan_srv_, clear_unknown_srv_, clear_costmaps_srv_;
00195 bool shutdown_costmaps_, clearing_roatation_allowed_, recovery_behavior_enabled_;
00196 double oscillation_timeout_, oscillation_distance_;
00197
00198 MoveBaseState state_;
00199 RecoveryTrigger recovery_trigger_;
00200
00201 ros::Time last_valid_plan_, last_valid_control_, last_oscillation_reset_;
00202 geometry_msgs::PoseStamped oscillation_pose_;
00203 pluginlib::ClassLoader<nav_core::BaseGlobalPlanner> bgp_loader_;
00204 pluginlib::ClassLoader<nav_core::BaseLocalPlanner> blp_loader_;
00205 pluginlib::ClassLoader<nav_core::RecoveryBehavior> recovery_loader_;
00206
00207 };
00208 };
00209 #endif
00210