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);
62 while (!queue_.empty())
68 if (i == start_i)
return c;
89 float cost = cost_interpreter_->getCost(next_index.
x, next_index.
y);
90 if (cost_interpreter_->isLethal(cost))
94 queue_.push(next_index);
bool add(const actionlib::TwoIntsGoal &req, actionlib::TwoIntsResult &res)
const float HIGH_POTENTIAL
void setValue(const unsigned int x, const unsigned int y, const T &value) override
NavGridInfo getInfo() const
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...
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)