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 NAV_MOVE_BASE_ACTION_H_
00038 #define NAV_MOVE_BASE_ACTION_H_
00039
00040 #include <vector>
00041 #include <string>
00042
00043 #include <ros/ros.h>
00044
00045 #include <actionlib/server/simple_action_server.h>
00046 #include <move_base_msgs/MoveBaseAction.h>
00047
00048 #include <nav_core/base_local_planner.h>
00049 #include <nav_core/base_global_planner.h>
00050 #include <nav_core/recovery_behavior.h>
00051 #include <geometry_msgs/PoseStamped.h>
00052 #include <costmap_2d/costmap_2d_ros.h>
00053 #include <costmap_2d/costmap_2d.h>
00054 #include <nav_msgs/GetPlan.h>
00055
00056 #include <pluginlib/class_loader.h>
00057 #include <std_srvs/Empty.h>
00058
00059 #include <dynamic_reconfigure/server.h>
00060 #include "move_base/MoveBaseConfig.h"
00061
00062 namespace move_base {
00063
00064 typedef actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> MoveBaseActionServer;
00065
00066 enum MoveBaseState {
00067 PLANNING,
00068 CONTROLLING,
00069 CLEARING
00070 };
00071
00072 enum RecoveryTrigger
00073 {
00074 PLANNING_R,
00075 CONTROLLING_R,
00076 OSCILLATION_R
00077 };
00078
00083 class MoveBase {
00084 public:
00090 MoveBase(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 clearCostmapsService(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 double distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2);
00168
00169 geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped& goal_pose_msg);
00170
00174 void wakePlanner(const ros::TimerEvent& event);
00175
00176 tf::TransformListener& tf_;
00177
00178 MoveBaseActionServer* as_;
00179
00180 boost::shared_ptr<nav_core::BaseLocalPlanner> tc_;
00181 costmap_2d::Costmap2DROS* planner_costmap_ros_, *controller_costmap_ros_;
00182
00183 boost::shared_ptr<nav_core::BaseGlobalPlanner> planner_;
00184 std::string robot_base_frame_, global_frame_;
00185
00186 std::vector<boost::shared_ptr<nav_core::RecoveryBehavior> > recovery_behaviors_;
00187 unsigned int recovery_index_;
00188
00189 tf::Stamped<tf::Pose> global_pose_;
00190 double planner_frequency_, controller_frequency_, inscribed_radius_, circumscribed_radius_;
00191 double planner_patience_, controller_patience_;
00192 double conservative_reset_dist_, clearing_radius_;
00193 ros::Publisher current_goal_pub_, vel_pub_, action_goal_pub_;
00194 ros::Subscriber goal_sub_;
00195 ros::ServiceServer make_plan_srv_, clear_costmaps_srv_;
00196 bool shutdown_costmaps_, clearing_rotation_allowed_, recovery_behavior_enabled_;
00197 double oscillation_timeout_, oscillation_distance_;
00198
00199 MoveBaseState state_;
00200 RecoveryTrigger recovery_trigger_;
00201
00202 ros::Time last_valid_plan_, last_valid_control_, last_oscillation_reset_;
00203 geometry_msgs::PoseStamped oscillation_pose_;
00204 pluginlib::ClassLoader<nav_core::BaseGlobalPlanner> bgp_loader_;
00205 pluginlib::ClassLoader<nav_core::BaseLocalPlanner> blp_loader_;
00206 pluginlib::ClassLoader<nav_core::RecoveryBehavior> recovery_loader_;
00207
00208
00209 std::vector<geometry_msgs::PoseStamped>* planner_plan_;
00210 std::vector<geometry_msgs::PoseStamped>* latest_plan_;
00211 std::vector<geometry_msgs::PoseStamped>* controller_plan_;
00212
00213
00214 bool runPlanner_;
00215 boost::mutex planner_mutex_;
00216 boost::condition_variable planner_cond_;
00217 geometry_msgs::PoseStamped planner_goal_;
00218 boost::thread* planner_thread_;
00219
00220
00221 boost::recursive_mutex configuration_mutex_;
00222 dynamic_reconfigure::Server<move_base::MoveBaseConfig> *dsrv_;
00223
00224 void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level);
00225
00226 move_base::MoveBaseConfig last_config_;
00227 move_base::MoveBaseConfig default_config_;
00228 bool setup_, p_freq_change_, c_freq_change_;
00229 bool new_global_plan_;
00230 };
00231 };
00232 #endif
00233