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 #ifndef DLUX_PLUGINS_ASTAR_H
00036 #define DLUX_PLUGINS_ASTAR_H
00037
00038 #include <dlux_global_planner/potential_calculator.h>
00039 #include <queue>
00040 #include <vector>
00041
00042 namespace dlux_plugins
00043 {
00044
00049 class AStar : public dlux_global_planner::PotentialCalculator
00050 {
00051 public:
00052
00053 void initialize(ros::NodeHandle& private_nh, nav_core2::Costmap::Ptr costmap,
00054 dlux_global_planner::CostInterpreter::Ptr cost_interpreter) override;
00055 unsigned int updatePotentials(dlux_global_planner::PotentialGrid& potential_grid,
00056 const geometry_msgs::Pose2D& start, const geometry_msgs::Pose2D& goal) override;
00057 protected:
00066 void add(dlux_global_planner::PotentialGrid& potential_grid, double prev_potential,
00067 const nav_grid::Index& index, const nav_grid::Index& start_index);
00068
00075 float getHeuristicValue(const nav_grid::Index& index, const nav_grid::Index& start_index) const;
00076
00080 struct QueueEntry
00081 {
00082 public:
00083 QueueEntry(nav_grid::Index index, float heuristic) : i(index), cost(heuristic) {}
00084 nav_grid::Index i;
00085 float cost;
00086 };
00087
00091 struct QueueEntryComparator
00092 {
00093 bool operator()(const QueueEntry& a, const QueueEntry& b) const
00094 {
00095 return a.cost > b.cost;
00096 }
00097 };
00098
00099
00100 using AStarQueue = std::priority_queue<QueueEntry, std::vector<QueueEntry>, QueueEntryComparator>;
00101 AStarQueue queue_;
00102 bool manhattan_heuristic_;
00103 bool use_kernel_;
00104 double minimum_requeue_change_;
00105 };
00106 }
00107
00108 #endif // DLUX_PLUGINS_ASTAR_H