56 const geometry_msgs::Pose2D& start,
const geometry_msgs::Pose2D& goal)
60 potential_grid.
reset();
65 potential_grid.
setValue(goal_i, 0.0);
76 unsigned int width_bound = potential_grid.
getWidth() - 1, height_bound = potential_grid.
getHeight() - 1;
86 if (i == start_i)
return c;
88 double prev_potential = potential_grid(i);
90 if (i.
x < width_bound)
94 if (i.
y < height_bound)
117 new_potential = prev_potential + cost;
123 potential_grid.
setValue(index, new_potential);
127 inline unsigned int uintDiff(
const unsigned int a,
const unsigned int b)
129 return (a > b) ? a - b : b - a;
134 unsigned int dx =
uintDiff(start_index.
x, index.
x);
135 unsigned int dy =
uintDiff(start_index.
y, index.
y);
138 distance =
static_cast<float>(dx + dy);
140 distance =
hypot(dx, dy);
NavGridInfo getInfo() const
unsigned int updatePotentials(dlux_global_planner::PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal) override
Helper Class for sorting indexes by their heuristic.
double minimum_requeue_change_
INLINE Rall1d< T, V, S > hypot(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
Potential calculator that explores using a distance heuristic (A*) but not the kernel function...
float getHeuristicValue(const nav_grid::Index &index, const nav_grid::Index &start_index) const
Calculate the heuristic value for a particular cell.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::priority_queue< QueueEntry, std::vector< QueueEntry >, QueueEntryComparator > AStarQueue
unsigned int getWidth() const
unsigned int getHeight() const
void setValue(const unsigned int x, const unsigned int y, const T &value) override
unsigned int uintDiff(const unsigned int a, const unsigned int b)
std::shared_ptr< CostInterpreter > Ptr
bool manhattan_heuristic_
static float calculateKernel(const PotentialGrid &potential_grid, unsigned char cost, unsigned int x, unsigned int y, CardinalDirection *upstream=nullptr)
std::shared_ptr< Costmap > Ptr
void initialize(ros::NodeHandle &private_nh, nav_core2::Costmap::Ptr costmap, dlux_global_planner::CostInterpreter::Ptr cost_interpreter) override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void add(dlux_global_planner::PotentialGrid &potential_grid, double prev_potential, const nav_grid::Index &index, const nav_grid::Index &start_index)
Calculate the potential for index if not calculated already.
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)
CostInterpreter::Ptr cost_interpreter_