47                                       const geometry_msgs::Pose2D& start, 
const geometry_msgs::Pose2D& goal,
    51   nav_2d_msgs::Path2D path;
    54   unsigned int current_x = 0, current_y = 0;
    58   geometry_msgs::Pose2D current;
    59   current.x = current_x + 0.5;
    60   current.y = current_y + 0.5;
    61   path.poses.push_back(current);
    63   unsigned int goal_index = potential_grid.
getIndex(goal.x, goal.y);
    66   while (potential_grid.
getIndex(current_x, current_y) != goal_index)
    68     float min_val = std::numeric_limits<float>::max();
    69     unsigned int min_x = 0, min_y = 0;
    71     for (
int xd = -1; xd <= 1; xd++)
    73       if ((current_x == 0 && xd == -1) || (current_x == info.
width - 1 && xd == 1)) 
continue;
    74       for (
int yd = -1; yd <= 1; yd++)
    76         if ((current_y == 0 && yd == -1) || (current_y == info.
height - 1 && yd == 1)) 
continue;
    77         if (xd == 0 && yd == 0)
    79         unsigned int x = current_x + xd, 
y = current_y + yd;
    80         int index = potential_grid.
getIndex(x, y);
    81         if (potential_grid[index] < min_val)
    83           min_val = potential_grid[index];
    86           distance_sq = abs(xd) + abs(yd);
    99     path_cost += distance * cost_interpreter_->getCost(current_x, current_y);
   106     current.x = current_x + 0.5;
   107     current.y = current_y + 0.5;
   108     path.poses.push_back(current);
   109     path_cost += distance * cost_interpreter_->getCost(current_x, current_y);
   111   return mapPathToWorldPath(path, info);
 
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const 
unsigned int getIndex(unsigned int mx, unsigned int my) const 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
Traceback function that moves from cell to cell using any of the eight neighbors. ...
TFSIMD_FORCE_INLINE const tfScalar & x() const 
NavGridInfo getInfo() const 
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)