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/grid_path.h>
00036 #include <nav_grid/coordinate_conversion.h>
00037 #include <nav_core2/exceptions.h>
00038 #include <limits>
00039 #include <pluginlib/class_list_macros.h>
00040
00041 PLUGINLIB_EXPORT_CLASS(dlux_plugins::GridPath, dlux_global_planner::Traceback)
00042
00043 namespace dlux_plugins
00044 {
00045
00046 nav_2d_msgs::Path2D GridPath::getPath(const dlux_global_planner::PotentialGrid& potential_grid,
00047 const geometry_msgs::Pose2D& start, const geometry_msgs::Pose2D& goal,
00048 double& path_cost)
00049 {
00050 const nav_grid::NavGridInfo& info = potential_grid.getInfo();
00051 nav_2d_msgs::Path2D path;
00052 path_cost = 0.0;
00053
00054 unsigned int current_x = 0, current_y = 0;
00055 worldToGridBounded(info, start.x, start.y, current_x, current_y);
00056
00057
00058 geometry_msgs::Pose2D current;
00059 current.x = current_x + 0.5;
00060 current.y = current_y + 0.5;
00061 path.poses.push_back(current);
00062
00063 unsigned int goal_index = potential_grid.getIndex(goal.x, goal.y);
00064
00065
00066 while (potential_grid.getIndex(current_x, current_y) != goal_index)
00067 {
00068 float min_val = std::numeric_limits<float>::max();
00069 unsigned int min_x = 0, min_y = 0;
00070 int distance_sq = 0;
00071 for (int xd = -1; xd <= 1; xd++)
00072 {
00073 if ((current_x == 0 && xd == -1) || (current_x == info.width - 1 && xd == 1)) continue;
00074 for (int yd = -1; yd <= 1; yd++)
00075 {
00076 if ((current_y == 0 && yd == -1) || (current_y == info.height - 1 && yd == 1)) continue;
00077 if (xd == 0 && yd == 0)
00078 continue;
00079 unsigned int x = current_x + xd, y = current_y + yd;
00080 int index = potential_grid.getIndex(x, y);
00081 if (potential_grid[index] < min_val)
00082 {
00083 min_val = potential_grid[index];
00084 min_x = x;
00085 min_y = y;
00086 distance_sq = abs(xd) + abs(yd);
00087 }
00088 }
00089 }
00090 if (distance_sq == 0)
00091 throw nav_core2::PlannerException("Reached dead end in traceback.");
00092
00093 double distance;
00094 if (distance_sq == 1)
00095 distance = 0.5;
00096 else
00097 distance = M_SQRT1_2;
00098
00099 path_cost += distance * cost_interpreter_->getCost(current_x, current_y);
00100
00101
00102 current_x = min_x;
00103 current_y = min_y;
00104
00105
00106 current.x = current_x + 0.5;
00107 current.y = current_y + 0.5;
00108 path.poses.push_back(current);
00109 path_cost += distance * cost_interpreter_->getCost(current_x, current_y);
00110 }
00111 return mapPathToWorldPath(path, info);
00112 }
00113
00114 }