46 const geometry_msgs::Pose2D& start,
const geometry_msgs::Pose2D& goal,
49 nav_2d_msgs::Path2D path;
52 unsigned int current_x = 0, current_y = 0;
56 geometry_msgs::Pose2D current;
57 current.x = current_x + 0.5;
58 current.y = current_y + 0.5;
59 path.poses.push_back(current);
62 unsigned int goal_index = potential_grid.
getIndex(goal.x, goal.y);
65 while (potential_grid.
getIndex(current_x, current_y) != goal_index)
67 float min_val = std::numeric_limits<float>::max();
68 unsigned int min_x = 0, min_y = 0;
77 index = potential_grid.
getIndex(x, y);
78 if (potential_grid[index] < min_val)
80 min_val = potential_grid[index];
85 if (current_x < potential_grid.
getWidth() - 1)
89 index = potential_grid.
getIndex(x, y);
90 if (potential_grid[index] < min_val)
92 min_val = potential_grid[index];
101 index = potential_grid.
getIndex(x, y);
102 if (potential_grid[index] < min_val)
104 min_val = potential_grid[index];
109 if (current_y < potential_grid.
getHeight() - 1)
113 index = potential_grid.
getIndex(x, y);
114 if (potential_grid[index] < min_val)
116 min_val = potential_grid[index];
122 if (min_val == std::numeric_limits<float>::max())
130 current.x = current_x + 0.5;
131 current.y = current_y + 0.5;
132 path.poses.push_back(current);
NavGridInfo getInfo() const
nav_2d_msgs::Path2D mapPathToWorldPath(const nav_2d_msgs::Path2D &original, const nav_grid::NavGridInfo &info)
nav_2d_msgs::Path2D getPath(const dlux_global_planner::PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal, double &path_cost) override
Traceback function that moves from cell to cell using only the four neighbors.
unsigned int getWidth() const
unsigned int getHeight() const
CostInterpreter::Ptr cost_interpreter_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)
unsigned int getIndex(unsigned int mx, unsigned int my) const