Go to the documentation of this file.00001 #ifndef _PLANNERCORE_H
00002 #define _PLANNERCORE_H
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
00038
00039
00040 #define POT_HIGH 1.0e10 // unassigned cell potential
00041 #include <ros/ros.h>
00042 #include <costmap_2d/costmap_2d.h>
00043 #include <geometry_msgs/PoseStamped.h>
00044 #include <geometry_msgs/Point.h>
00045 #include <nav_msgs/Path.h>
00046 #include <tf/transform_datatypes.h>
00047 #include <vector>
00048 #include <nav_core/base_global_planner.h>
00049 #include <nav_msgs/GetPlan.h>
00050 #include <dynamic_reconfigure/server.h>
00051 #include <global_planner/potential_calculator.h>
00052 #include <global_planner/expander.h>
00053 #include <global_planner/traceback.h>
00054 #include <global_planner/GlobalPlannerConfig.h>
00055
00056 namespace global_planner {
00057
00058 class Expander;
00059 class GridPath;
00060
00066 class GlobalPlanner : public nav_core::BaseGlobalPlanner {
00067 public:
00071 GlobalPlanner();
00072
00079 GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
00080
00086 void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00087
00088 void initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
00089
00097 bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
00098 std::vector<geometry_msgs::PoseStamped>& plan);
00099
00108 bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, double tolerance,
00109 std::vector<geometry_msgs::PoseStamped>& plan);
00110
00116 bool computePotential(const geometry_msgs::Point& world_point);
00117
00128 bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y,
00129 const geometry_msgs::PoseStamped& goal,
00130 std::vector<geometry_msgs::PoseStamped>& plan);
00131
00137 double getPointPotential(const geometry_msgs::Point& world_point);
00138
00144 bool validPointPotential(const geometry_msgs::Point& world_point);
00145
00152 bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance);
00153
00157 void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path);
00158
00159 ~GlobalPlanner() {
00160 }
00161
00162 bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
00163
00164 protected:
00165
00169 costmap_2d::Costmap2D* costmap_;
00170 std::string frame_id_;
00171 ros::Publisher plan_pub_;
00172 bool initialized_, allow_unknown_, visualize_potential_;
00173
00174 private:
00175 void mapToWorld(double mx, double my, double& wx, double& wy);
00176 bool worldToMap(double wx, double wy, double& mx, double& my);
00177 void clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my);
00178 void publishPotential(float* potential);
00179
00180 double planner_window_x_, planner_window_y_, default_tolerance_;
00181 std::string tf_prefix_;
00182 boost::mutex mutex_;
00183 ros::ServiceServer make_plan_srv_;
00184
00185 PotentialCalculator* p_calc_;
00186 Expander* planner_;
00187 Traceback* path_maker_;
00188
00189 bool publish_potential_;
00190 ros::Publisher potential_pub_;
00191 int publish_scale_;
00192
00193 void outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value);
00194 unsigned char* cost_array_;
00195 float* potential_array_;
00196 unsigned int start_x_, start_y_, end_x_, end_y_;
00197
00198 bool old_navfn_behavior_;
00199 float convert_offset_;
00200
00201 dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig> *dsrv_;
00202 void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level);
00203
00204 };
00205
00206 }
00207
00208 #endif