#include <hyper_dijkstra.h>
Classes | |
struct | AdjacencyMapEntry |
struct | CostFunction |
struct | TreeAction |
Public Types | |
typedef std::map < HyperGraph::Vertex *, AdjacencyMapEntry > | AdjacencyMap |
Public Member Functions | |
AdjacencyMap & | adjacencyMap () |
HyperGraph * | graph () |
HyperDijkstra (HyperGraph *g) | |
void | shortestPaths (HyperGraph::Vertex *v, HyperDijkstra::CostFunction *cost, double maxDistance=std::numeric_limits< double >::max(), double comparisonConditioner=1e-3, bool directed=false, double maxEdgeCost=std::numeric_limits< double >::max()) |
void | shortestPaths (HyperGraph::VertexSet &vset, HyperDijkstra::CostFunction *cost, double maxDistance=std::numeric_limits< double >::max(), double comparisonConditioner=1e-3, bool directed=false, double maxEdgeCost=std::numeric_limits< double >::max()) |
HyperGraph::VertexSet & | visited () |
Static Public Member Functions | |
static void | computeTree (AdjacencyMap &amap) |
static void | visitAdjacencyMap (AdjacencyMap &amap, TreeAction *action, bool useDistance=false) |
Protected Member Functions | |
void | reset () |
Protected Attributes | |
AdjacencyMap | _adjacencyMap |
HyperGraph * | _graph |
HyperGraph::VertexSet | _visited |
Definition at line 27 of file hyper_dijkstra.h.
typedef std::map<HyperGraph::Vertex*, AdjacencyMapEntry> g2o::HyperDijkstra::AdjacencyMap |
Definition at line 58 of file hyper_dijkstra.h.
Definition at line 49 of file hyper_dijkstra.cpp.
AdjacencyMap& g2o::HyperDijkstra::adjacencyMap | ( | ) | [inline] |
Definition at line 61 of file hyper_dijkstra.h.
void g2o::HyperDijkstra::computeTree | ( | AdjacencyMap & | amap | ) | [static] |
Definition at line 138 of file hyper_dijkstra.cpp.
HyperGraph* g2o::HyperDijkstra::graph | ( | ) | [inline] |
Definition at line 62 of file hyper_dijkstra.h.
void g2o::HyperDijkstra::reset | ( | ) | [protected] |
Definition at line 57 of file hyper_dijkstra.cpp.
void g2o::HyperDijkstra::shortestPaths | ( | HyperGraph::Vertex * | v, |
HyperDijkstra::CostFunction * | cost, | ||
double | maxDistance = std::numeric_limits< double >::max() , |
||
double | comparisonConditioner = 1e-3 , |
||
bool | directed = false , |
||
double | maxEdgeCost = std::numeric_limits< double >::max() |
||
) |
Definition at line 130 of file hyper_dijkstra.cpp.
void g2o::HyperDijkstra::shortestPaths | ( | HyperGraph::VertexSet & | vset, |
HyperDijkstra::CostFunction * | cost, | ||
double | maxDistance = std::numeric_limits< double >::max() , |
||
double | comparisonConditioner = 1e-3 , |
||
bool | directed = false , |
||
double | maxEdgeCost = std::numeric_limits< double >::max() |
||
) |
Definition at line 74 of file hyper_dijkstra.cpp.
void g2o::HyperDijkstra::visitAdjacencyMap | ( | AdjacencyMap & | amap, |
TreeAction * | action, | ||
bool | useDistance = false |
||
) | [static] |
Definition at line 160 of file hyper_dijkstra.cpp.
HyperGraph::VertexSet& g2o::HyperDijkstra::visited | ( | ) | [inline] |
Definition at line 60 of file hyper_dijkstra.h.
AdjacencyMap g2o::HyperDijkstra::_adjacencyMap [protected] |
Definition at line 85 of file hyper_dijkstra.h.
HyperGraph* g2o::HyperDijkstra::_graph [protected] |
Definition at line 87 of file hyper_dijkstra.h.
HyperGraph::VertexSet g2o::HyperDijkstra::_visited [protected] |
Definition at line 86 of file hyper_dijkstra.h.