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 ClearingState {
00070 CONSERVATIVE_RESET,
00071 IN_PLACE_ROTATION_1,
00072 EXECUTE_ROTATE_1,
00073 IN_PLACE_ROTATION_2,
00074 EXECUTE_ROTATE_2,
00075 AGGRESSIVE_RESET,
00076 ABORT
00077 };
00078
00083 class MoveBase {
00084 public:
00090 MoveBase(std::string name, tf::TransformListener& tf);
00091
00095 virtual ~MoveBase();
00096
00103 bool executeCycle(geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& global_plan);
00104
00105 private:
00112 bool clearUnknownService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
00113
00120 bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp);
00121
00128 bool makePlan(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
00129
00135 bool loadRecoveryBehaviors(ros::NodeHandle node);
00136
00140 void loadDefaultRecoveryBehaviors();
00141
00147 void clearCostmapWindows(double size_x, double size_y);
00148
00152 void publishZeroVelocity();
00153
00157 void resetState();
00158
00159 void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal);
00160
00161 void planThread();
00162
00163 void executeCb(const move_base_msgs::MoveBaseGoalConstPtr& move_base_goal);
00164
00165 bool isQuaternionValid(const geometry_msgs::Quaternion& q);
00166
00167 geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg);
00168
00169 tf::TransformListener& tf_;
00170
00171 MoveBaseActionServer* as_;
00172
00173 nav_core::BaseLocalPlanner* tc_;
00174 costmap_2d::Costmap2DROS* planner_costmap_ros_, *controller_costmap_ros_;
00175
00176 nav_core::BaseGlobalPlanner* planner_;
00177 std::string robot_base_frame_, global_frame_;
00178
00179 std::vector<boost::shared_ptr<nav_core::RecoveryBehavior> > recovery_behaviors_;
00180 unsigned int recovery_index_;
00181
00182 tf::Stamped<tf::Pose> global_pose_;
00183 double controller_frequency_, inscribed_radius_, circumscribed_radius_;
00184 double planner_frequency_;
00185 double planner_patience_, controller_patience_;
00186 double conservative_reset_dist_, clearing_radius_;
00187 ros::Publisher current_goal_pub_, vel_pub_, action_goal_pub_;
00188 ros::Subscriber goal_sub_;
00189 ros::ServiceServer make_plan_srv_, clear_unknown_srv_;
00190 bool shutdown_costmaps_, clearing_roatation_allowed_, recovery_behavior_enabled_;
00191 bool control_failure_recovery_;
00192
00193 MoveBaseState state_;
00194 ClearingState clearing_state_;
00195
00196 ros::Time last_valid_plan_, last_valid_control_, last_plan_swap_;
00197 pluginlib::ClassLoader<nav_core::BaseGlobalPlanner> bgp_loader_;
00198 pluginlib::ClassLoader<nav_core::BaseLocalPlanner> blp_loader_;
00199 pluginlib::ClassLoader<nav_core::RecoveryBehavior> recovery_loader_;
00200
00201
00202
00203 std::vector<geometry_msgs::PoseStamped>* planner_plan;
00204 std::vector<geometry_msgs::PoseStamped>* latest_plan;
00205 std::vector<geometry_msgs::PoseStamped>* controller_plan;
00206 boost::mutex plan_lock;
00207
00208
00209 bool runPlanner;
00210 boost::mutex planner_mutex;
00211 boost::unique_lock<boost::mutex>* planner_lock;
00212 boost::condition_variable planner_cond;
00213 geometry_msgs::PoseStamped planner_goal;
00214 boost::thread* planner_thread;
00215
00216 };
00217 };
00218 #endif
00219