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/von_neumann_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::VonNeumannPath, dlux_global_planner::Traceback)
00042
00043 namespace dlux_plugins
00044 {
00045 nav_2d_msgs::Path2D VonNeumannPath::getPath(const dlux_global_planner::PotentialGrid& potential_grid,
00046 const geometry_msgs::Pose2D& start, const geometry_msgs::Pose2D& goal,
00047 double& path_cost)
00048 {
00049 nav_2d_msgs::Path2D path;
00050 path_cost = 0.0;
00051
00052 unsigned int current_x = 0, current_y = 0;
00053 worldToGridBounded(potential_grid.getInfo(), start.x, start.y, current_x, current_y);
00054
00055
00056 geometry_msgs::Pose2D current;
00057 current.x = current_x + 0.5;
00058 current.y = current_y + 0.5;
00059 path.poses.push_back(current);
00060 path_cost += cost_interpreter_->getCost(current_x, current_y);
00061
00062 unsigned int goal_index = potential_grid.getIndex(goal.x, goal.y);
00063
00064
00065 while (potential_grid.getIndex(current_x, current_y) != goal_index)
00066 {
00067 float min_val = std::numeric_limits<float>::max();
00068 unsigned int min_x = 0, min_y = 0;
00069 unsigned int x, y;
00070 int index;
00071
00072
00073 if (current_x > 0)
00074 {
00075 x = current_x - 1;
00076 y = current_y;
00077 index = potential_grid.getIndex(x, y);
00078 if (potential_grid[index] < min_val)
00079 {
00080 min_val = potential_grid[index];
00081 min_x = x;
00082 min_y = y;
00083 }
00084 }
00085 if (current_x < potential_grid.getWidth() - 1)
00086 {
00087 x = current_x + 1;
00088 y = current_y;
00089 index = potential_grid.getIndex(x, y);
00090 if (potential_grid[index] < min_val)
00091 {
00092 min_val = potential_grid[index];
00093 min_x = x;
00094 min_y = y;
00095 }
00096 }
00097 if (current_y > 0)
00098 {
00099 x = current_x;
00100 y = current_y - 1;
00101 index = potential_grid.getIndex(x, y);
00102 if (potential_grid[index] < min_val)
00103 {
00104 min_val = potential_grid[index];
00105 min_x = x;
00106 min_y = y;
00107 }
00108 }
00109 if (current_y < potential_grid.getHeight() - 1)
00110 {
00111 x = current_x;
00112 y = current_y + 1;
00113 index = potential_grid.getIndex(x, y);
00114 if (potential_grid[index] < min_val)
00115 {
00116 min_val = potential_grid[index];
00117 min_x = x;
00118 min_y = y;
00119 }
00120 }
00121
00122 if (min_val == std::numeric_limits<float>::max())
00123 throw nav_core2::PlannerException("Reached dead end in traceback.");
00124
00125
00126 current_x = min_x;
00127 current_y = min_y;
00128
00129
00130 current.x = current_x + 0.5;
00131 current.y = current_y + 0.5;
00132 path.poses.push_back(current);
00133 path_cost += cost_interpreter_->getCost(current_x, current_y);
00134 }
00135 return mapPathToWorldPath(path, potential_grid.getInfo());
00136 }
00137
00138 }