Potential calculator that explores the potential breadth first while using the kernel function. More...
#include <dijkstra.h>
Public Member Functions | |
unsigned int | updatePotentials (dlux_global_planner::PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal) override |
Public Member Functions inherited from dlux_global_planner::PotentialCalculator | |
virtual void | initialize (ros::NodeHandle &private_nh, nav_core2::Costmap::Ptr costmap, CostInterpreter::Ptr cost_interpreter) |
PotentialCalculator () | |
virtual | ~PotentialCalculator ()=default |
Protected Member Functions | |
void | add (dlux_global_planner::PotentialGrid &potential_grid, nav_grid::Index next_index) |
Calculate the potential for next_index if not calculated already. More... | |
Protected Attributes | |
std::queue< nav_grid::Index > | queue_ |
Protected Attributes inherited from dlux_global_planner::PotentialCalculator | |
CostInterpreter::Ptr | cost_interpreter_ |
Potential calculator that explores the potential breadth first while using the kernel function.
Definition at line 47 of file dijkstra.h.
|
protected |
Calculate the potential for next_index if not calculated already.
potential_grid | Potential grid |
next_index | Coordinates of cell to calculate |
Definition at line 84 of file dijkstra.cpp.
|
overridevirtual |
Implements dlux_global_planner::PotentialCalculator.
Definition at line 46 of file dijkstra.cpp.
|
protected |
Definition at line 62 of file dijkstra.h.