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/orientation_filter.h>
00055 #include <global_planner/GlobalPlannerConfig.h>
00056
00057 namespace global_planner {
00058
00059 class Expander;
00060 class GridPath;
00061
00067 class GlobalPlanner : public nav_core::BaseGlobalPlanner {
00068 public:
00072 GlobalPlanner();
00073
00080 GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
00081
00085 ~GlobalPlanner();
00086
00092 void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00093
00094 void initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id);
00095
00103 bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
00104 std::vector<geometry_msgs::PoseStamped>& plan);
00105
00114 bool makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal, double tolerance,
00115 std::vector<geometry_msgs::PoseStamped>& plan);
00116
00122 bool computePotential(const geometry_msgs::Point& world_point);
00123
00134 bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y,
00135 const geometry_msgs::PoseStamped& goal,
00136 std::vector<geometry_msgs::PoseStamped>& plan);
00137
00143 double getPointPotential(const geometry_msgs::Point& world_point);
00144
00150 bool validPointPotential(const geometry_msgs::Point& world_point);
00151
00158 bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance);
00159
00163 void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path);
00164
00165 bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
00166
00167 protected:
00168
00172 costmap_2d::Costmap2D* costmap_;
00173 std::string frame_id_;
00174 ros::Publisher plan_pub_;
00175 bool initialized_, allow_unknown_, visualize_potential_;
00176
00177 private:
00178 void mapToWorld(double mx, double my, double& wx, double& wy);
00179 bool worldToMap(double wx, double wy, double& mx, double& my);
00180 void clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my);
00181 void publishPotential(float* potential);
00182
00183 double planner_window_x_, planner_window_y_, default_tolerance_;
00184 std::string tf_prefix_;
00185 boost::mutex mutex_;
00186 ros::ServiceServer make_plan_srv_;
00187
00188 PotentialCalculator* p_calc_;
00189 Expander* planner_;
00190 Traceback* path_maker_;
00191 OrientationFilter* orientation_filter_;
00192
00193 bool publish_potential_;
00194 ros::Publisher potential_pub_;
00195 int publish_scale_;
00196
00197 void outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value);
00198 unsigned char* cost_array_;
00199 float* potential_array_;
00200 unsigned int start_x_, start_y_, end_x_, end_y_;
00201
00202 bool old_navfn_behavior_;
00203 float convert_offset_;
00204
00205 dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig> *dsrv_;
00206 void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level);
00207
00208 };
00209
00210 }
00211
00212 #endif