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 |
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. | |
Protected Attributes | |
std::queue< nav_grid::Index > | queue_ |
Potential calculator that explores the potential breadth first while using the kernel function.
Definition at line 47 of file dijkstra.h.
void dlux_plugins::Dijkstra::add | ( | dlux_global_planner::PotentialGrid & | potential_grid, |
nav_grid::Index | next_index | ||
) | [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.
unsigned int dlux_plugins::Dijkstra::updatePotentials | ( | dlux_global_planner::PotentialGrid & | potential_grid, |
const geometry_msgs::Pose2D & | start, | ||
const geometry_msgs::Pose2D & | goal | ||
) | [override] |
Definition at line 46 of file dijkstra.cpp.
std::queue<nav_grid::Index> dlux_plugins::Dijkstra::queue_ [protected] |
Definition at line 62 of file dijkstra.h.