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 |
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. | |
| float | getHeuristicValue (const nav_grid::Index &index, const nav_grid::Index &start_index) const |
| Calculate the heuristic value for a particular cell. | |
Protected Attributes | |
| bool | manhattan_heuristic_ |
| double | minimum_requeue_change_ |
| AStarQueue | queue_ |
| bool | use_kernel_ |
Potential calculator that explores using a distance heuristic (A*) but not the kernel function.
| void dlux_plugins::AStar::add | ( | dlux_global_planner::PotentialGrid & | potential_grid, |
| double | prev_potential, | ||
| const nav_grid::Index & | index, | ||
| const nav_grid::Index & | start_index | ||
| ) | [protected] |
| float dlux_plugins::AStar::getHeuristicValue | ( | const nav_grid::Index & | index, |
| const nav_grid::Index & | start_index | ||
| ) | const [protected] |
| void dlux_plugins::AStar::initialize | ( | ros::NodeHandle & | private_nh, |
| nav_core2::Costmap::Ptr | costmap, | ||
| dlux_global_planner::CostInterpreter::Ptr | cost_interpreter | ||
| ) | [override, virtual] |
Reimplemented from dlux_global_planner::PotentialCalculator.
| unsigned int dlux_plugins::AStar::updatePotentials | ( | dlux_global_planner::PotentialGrid & | potential_grid, |
| const geometry_msgs::Pose2D & | start, | ||
| const geometry_msgs::Pose2D & | goal | ||
| ) | [override] |
bool dlux_plugins::AStar::manhattan_heuristic_ [protected] |
double dlux_plugins::AStar::minimum_requeue_change_ [protected] |
AStarQueue dlux_plugins::AStar::queue_ [protected] |
bool dlux_plugins::AStar::use_kernel_ [protected] |