Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
dlux_plugins::AStar Class Reference

Potential calculator that explores using a distance heuristic (A*) but not the kernel function. More...

#include <astar.h>

Inheritance diagram for dlux_plugins::AStar:
Inheritance graph
[legend]

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_
 

Detailed Description

Potential calculator that explores using a distance heuristic (A*) but not the kernel function.

Definition at line 49 of file astar.h.

Member Typedef Documentation

using dlux_plugins::AStar::AStarQueue = std::priority_queue<QueueEntry, std::vector<QueueEntry>, QueueEntryComparator>
protected

Definition at line 100 of file astar.h.

Member Function Documentation

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

Calculate the potential for index if not calculated already.

Parameters
potential_gridPotential grid
prev_potentialPotential of the previous cell
indexCoordinates of cell to calculate
start_indexCoordinates of start cell (for heuristic calculation)

Definition at line 103 of file astar.cpp.

float dlux_plugins::AStar::getHeuristicValue ( const nav_grid::Index index,
const nav_grid::Index start_index 
) const
protected

Calculate the heuristic value for a particular cell.

Parameters
indexCoordinates of cell to calculate
start_indexCoordinates of start cell

Definition at line 132 of file astar.cpp.

void dlux_plugins::AStar::initialize ( ros::NodeHandle private_nh,
nav_core2::Costmap::Ptr  costmap,
dlux_global_planner::CostInterpreter::Ptr  cost_interpreter 
)
overridevirtual

Reimplemented from dlux_global_planner::PotentialCalculator.

Definition at line 46 of file astar.cpp.

unsigned int dlux_plugins::AStar::updatePotentials ( dlux_global_planner::PotentialGrid potential_grid,
const geometry_msgs::Pose2D &  start,
const geometry_msgs::Pose2D &  goal 
)
overridevirtual

Implements dlux_global_planner::PotentialCalculator.

Definition at line 55 of file astar.cpp.

Member Data Documentation

bool dlux_plugins::AStar::manhattan_heuristic_
protected

Definition at line 102 of file astar.h.

double dlux_plugins::AStar::minimum_requeue_change_
protected

Definition at line 104 of file astar.h.

AStarQueue dlux_plugins::AStar::queue_
protected

Definition at line 101 of file astar.h.

bool dlux_plugins::AStar::use_kernel_
protected

Definition at line 103 of file astar.h.


The documentation for this class was generated from the following files:


dlux_plugins
Author(s):
autogenerated on Wed Jun 26 2019 20:06:32