Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dlux_plugins::Dijkstra Class Reference

Potential calculator that explores the potential breadth first while using the kernel function. More...

#include <dijkstra.h>

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

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::Indexqueue_
 
- Protected Attributes inherited from dlux_global_planner::PotentialCalculator
CostInterpreter::Ptr cost_interpreter_
 

Detailed Description

Potential calculator that explores the potential breadth first while using the kernel function.

Definition at line 47 of file dijkstra.h.

Member Function Documentation

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.

Parameters
potential_gridPotential grid
next_indexCoordinates 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 
)
overridevirtual

Implements dlux_global_planner::PotentialCalculator.

Definition at line 46 of file dijkstra.cpp.

Member Data Documentation

std::queue<nav_grid::Index> dlux_plugins::Dijkstra::queue_
protected

Definition at line 62 of file dijkstra.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