Potential calculator that explores using a distance heuristic (A*) but not the kernel function. More...
#include <astar.h>
Classes | |
struct | QueueEntry |
Helper Class for sorting indexes by their heuristic. More... | |
struct | QueueEntryComparator |
Comparator for sorting the QueueEntrys. More... | |
Public Member Functions | |
void | initialize (ros::NodeHandle &private_nh, nav_core2::Costmap::Ptr costmap, dlux_global_planner::CostInterpreter::Ptr cost_interpreter) override |
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 | |
PotentialCalculator () | |
virtual | ~PotentialCalculator ()=default |
Protected Types | |
using | AStarQueue = std::priority_queue< QueueEntry, std::vector< QueueEntry >, QueueEntryComparator > |
Protected Member Functions | |
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. More... | |
float | getHeuristicValue (const nav_grid::Index &index, const nav_grid::Index &start_index) const |
Calculate the heuristic value for a particular cell. More... | |
Protected Attributes | |
bool | manhattan_heuristic_ |
double | minimum_requeue_change_ |
AStarQueue | queue_ |
bool | use_kernel_ |
Protected Attributes inherited from dlux_global_planner::PotentialCalculator | |
CostInterpreter::Ptr | cost_interpreter_ |
Potential calculator that explores using a distance heuristic (A*) but not the kernel function.
|
protected |
|
protected |
|
protected |
|
overridevirtual |
Reimplemented from dlux_global_planner::PotentialCalculator.
|
overridevirtual |
Implements dlux_global_planner::PotentialCalculator.
|
protected |
|
protected |