Ignition Math

API Reference

6.4.0
GraphAlgorithms.hh File Reference
#include <functional>
#include <list>
#include <map>
#include <queue>
#include <stack>
#include <utility>
#include <vector>
#include <ignition/math/config.hh>
#include "ignition/math/graph/Graph.hh"
#include "ignition/math/Helpers.hh"

Go to the source code of this file.

Namespaces

 ignition
 
 ignition::math
 Math classes and function useful in robot applications.
 
 ignition::math::graph
 

Typedefs

using CostInfo = std::pair< double, VertexId >
 Used in Dijkstra. For a given source vertex, this pair represents the cost (first element) to reach a destination vertex (second element). More...
 

Functions

template<typename V , typename E , typename EdgeType >
std::vector< VertexId > BreadthFirstSort (const Graph< V, E, EdgeType > &_graph, const VertexId &_from)
 Breadth first sort (BFS). Starting from the vertex == _from, it traverses the graph exploring the neighbors first, before moving to the next level neighbors. More...
 
template<typename V , typename E >
std::vector< UndirectedGraph< V, E > > ConnectedComponents (const UndirectedGraph< V, E > &_graph)
 Calculate the connected components of an undirected graph. A connected component of an undirected graph is a subgraph in which any two vertices are connected to each other by paths, and which is connected to no additional vertices in the supergraph. More...
 
template<typename V , typename E , typename EdgeType >
std::vector< VertexId > DepthFirstSort (const Graph< V, E, EdgeType > &_graph, const VertexId &_from)
 Depth first sort (DFS). Starting from the vertex == _from, it visits the graph as far as possible along each branch before backtracking. More...
 
template<typename V , typename E , typename EdgeType >
std::map< VertexId, CostInfo > Dijkstra (const Graph< V, E, EdgeType > &_graph, const VertexId &_from, const VertexId &_to=kNullId)
 Dijkstra algorithm. Find the shortest path between the vertices in a graph. If only a graph and a source vertex is provided, the algorithm will find shortest paths from the source vertex to all other vertices in the graph. If an additional destination vertex is provided, the algorithm will stop when the shortest path is found between the source and destination vertex. More...
 
template<typename V , typename E >
UndirectedGraph< V, E > ToUndirectedGraph (const DirectedGraph< V, E > &_graph)
 Copy a DirectedGraph to an UndirectedGraph with the same vertices and edges. More...