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 #include <dlux_plugins/dijkstra.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 #include <nav_core2/exceptions.h>
00038 #include <dlux_global_planner/kernel_function.h>
00039 #include <pluginlib/class_list_macros.h>
00040 #include <queue>
00041
00042 PLUGINLIB_EXPORT_CLASS(dlux_plugins::Dijkstra, dlux_global_planner::PotentialCalculator)
00043
00044 namespace dlux_plugins
00045 {
00046 unsigned int Dijkstra::updatePotentials(dlux_global_planner::PotentialGrid& potential_grid,
00047 const geometry_msgs::Pose2D& start, const geometry_msgs::Pose2D& goal)
00048 {
00049 const nav_grid::NavGridInfo& info = potential_grid.getInfo();
00050 queue_ = std::queue<nav_grid::Index>();
00051 potential_grid.reset();
00052
00053 nav_grid::Index goal_i;
00054 worldToGridBounded(info, goal.x, goal.y, goal_i.x, goal_i.y);
00055 queue_.push(goal_i);
00056 potential_grid.setValue(goal_i, 0.0);
00057
00058 nav_grid::Index start_i;
00059 worldToGridBounded(info, start.x, start.y, start_i.x, start_i.y);
00060 unsigned int c = 0;
00061
00062 while (!queue_.empty())
00063 {
00064 nav_grid::Index i = queue_.front();
00065 queue_.pop();
00066 c++;
00067
00068 if (i == start_i) return c;
00069
00070 if (i.x > 0)
00071 add(potential_grid, nav_grid::Index(i.x - 1, i.y));
00072 if (i.y > 0)
00073 add(potential_grid, nav_grid::Index(i.x, i.y - 1));
00074
00075 if (i.x < info.width - 1)
00076 add(potential_grid, nav_grid::Index(i.x + 1, i.y));
00077 if (i.y < info.height - 1)
00078 add(potential_grid, nav_grid::Index(i.x, i.y + 1));
00079 }
00080
00081 throw nav_core2::NoGlobalPathException();
00082 }
00083
00084 void Dijkstra::add(dlux_global_planner::PotentialGrid& potential_grid, nav_grid::Index next_index)
00085 {
00086 if (potential_grid(next_index.x, next_index.y) < dlux_global_planner::HIGH_POTENTIAL)
00087 return;
00088
00089 float cost = cost_interpreter_->getCost(next_index.x, next_index.y);
00090 if (cost_interpreter_->isLethal(cost))
00091 return;
00092 potential_grid.setValue(next_index,
00093 dlux_global_planner::calculateKernel(potential_grid, cost, next_index.x, next_index.y));
00094 queue_.push(next_index);
00095 }
00096
00097 }