47 const geometry_msgs::Pose2D& start,
const geometry_msgs::Pose2D& goal)
50 queue_ = std::queue<nav_grid::Index>();
51 potential_grid.
reset();
56 potential_grid.
setValue(goal_i, 0.0);
68 if (i == start_i)
return c;
NavGridInfo getInfo() const
void add(dlux_global_planner::PotentialGrid &potential_grid, nav_grid::Index next_index)
Calculate the potential for next_index if not calculated already.
const float HIGH_POTENTIAL
void setValue(const unsigned int x, const unsigned int y, const T &value) override
unsigned int updatePotentials(dlux_global_planner::PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal) override
static float calculateKernel(const PotentialGrid &potential_grid, unsigned char cost, unsigned int x, unsigned int y, CardinalDirection *upstream=nullptr)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Potential calculator that explores the potential breadth first while using the kernel function...
std::queue< nav_grid::Index > queue_
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)
CostInterpreter::Ptr cost_interpreter_