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 #include <dlux_plugins/astar.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 #include <nav_core2/exceptions.h>
00038 #include <dlux_global_planner/kernel_function.h>
00039 #include <math.h>
00040 #include <pluginlib/class_list_macros.h>
00041
00042 PLUGINLIB_EXPORT_CLASS(dlux_plugins::AStar, dlux_global_planner::PotentialCalculator)
00043
00044 namespace dlux_plugins
00045 {
00046 void AStar::initialize(ros::NodeHandle& private_nh, nav_core2::Costmap::Ptr costmap,
00047 dlux_global_planner::CostInterpreter::Ptr cost_interpreter)
00048 {
00049 cost_interpreter_ = cost_interpreter;
00050 private_nh.param("manhattan_heuristic", manhattan_heuristic_, false);
00051 private_nh.param("use_kernel", use_kernel_, true);
00052 private_nh.param("minimum_requeue_change", minimum_requeue_change_, 1.0);
00053 }
00054
00055 unsigned int AStar::updatePotentials(dlux_global_planner::PotentialGrid& potential_grid,
00056 const geometry_msgs::Pose2D& start, const geometry_msgs::Pose2D& goal)
00057 {
00058 const nav_grid::NavGridInfo& info = potential_grid.getInfo();
00059 queue_ = AStarQueue();
00060 potential_grid.reset();
00061
00062 nav_grid::Index goal_i;
00063 worldToGridBounded(info, goal.x, goal.y, goal_i.x, goal_i.y);
00064 queue_.push(QueueEntry(goal_i, 0.0));
00065 potential_grid.setValue(goal_i, 0.0);
00066
00067
00068 nav_grid::Index start_i;
00069 worldToGridBounded(info, start.x, start.y, start_i.x, start_i.y);
00070
00071 if (potential_grid.getWidth() == 0 || potential_grid.getHeight() == 0)
00072 {
00073 return 0;
00074 }
00075
00076 unsigned int width_bound = potential_grid.getWidth() - 1, height_bound = potential_grid.getHeight() - 1;
00077 unsigned int c = 0;
00078
00079 while (queue_.size() > 0)
00080 {
00081 QueueEntry top = queue_.top();
00082 queue_.pop();
00083 c++;
00084
00085 nav_grid::Index i = top.i;
00086 if (i == start_i) return c;
00087
00088 double prev_potential = potential_grid(i);
00089
00090 if (i.x < width_bound)
00091 add(potential_grid, prev_potential, nav_grid::Index(i.x + 1, i.y), start_i);
00092 if (i.x > 0)
00093 add(potential_grid, prev_potential, nav_grid::Index(i.x - 1, i.y), start_i);
00094 if (i.y < height_bound)
00095 add(potential_grid, prev_potential, nav_grid::Index(i.x, i.y + 1), start_i);
00096 if (i.y > 0)
00097 add(potential_grid, prev_potential, nav_grid::Index(i.x, i.y - 1), start_i);
00098 }
00099
00100 throw nav_core2::NoGlobalPathException();
00101 }
00102
00103 void AStar::add(dlux_global_planner::PotentialGrid& potential_grid, double prev_potential,
00104 const nav_grid::Index& index, const nav_grid::Index& start_index)
00105 {
00106 float cost = cost_interpreter_->getCost(index.x, index.y);
00107 if (cost_interpreter_->isLethal(cost))
00108 return;
00109
00110 float new_potential;
00111 if (use_kernel_)
00112 {
00113 new_potential = dlux_global_planner::calculateKernel(potential_grid, cost, index.x, index.y);
00114 }
00115 else
00116 {
00117 new_potential = prev_potential + cost;
00118 }
00119
00120 if (new_potential >= potential_grid(index) || potential_grid(index) - new_potential < minimum_requeue_change_)
00121 return;
00122
00123 potential_grid.setValue(index, new_potential);
00124 queue_.push(QueueEntry(index, new_potential + getHeuristicValue(index, start_index)));
00125 }
00126
00127 inline unsigned int uintDiff(const unsigned int a, const unsigned int b)
00128 {
00129 return (a > b) ? a - b : b - a;
00130 }
00131
00132 float AStar::getHeuristicValue(const nav_grid::Index& index, const nav_grid::Index& start_index) const
00133 {
00134 unsigned int dx = uintDiff(start_index.x, index.x);
00135 unsigned int dy = uintDiff(start_index.y, index.y);
00136 float distance;
00137 if (manhattan_heuristic_)
00138 distance = static_cast<float>(dx + dy);
00139 else
00140 distance = hypot(dx, dy);
00141 return distance * cost_interpreter_->getNeutralCost();
00142 }
00143
00144 }