Classes | |
class | DirectedEdge |
A directed edge represents a connection between two vertices. The connection is unidirectional, it's only possible to traverse the edge in one direction (from the tail to the head). More... | |
class | Edge |
Generic edge class. An edge has two ends and some constraint between them. For example, a directed edge only allows traversing the edge in one direction. More... | |
struct | EdgeInitializer |
Used in the Graph constructors for uniform initialization. More... | |
class | Graph |
A generic graph class. Both vertices and edges can store user information. A vertex could be created passing a custom Id if needed, otherwise it will be choosen internally. The vertices also have a name that could be reused among other vertices if needed. This class supports the use of different edge types (e.g. directed or undirected edges). More... | |
class | UndirectedEdge |
An undirected edge represents a connection between two vertices. The connection is bidirectional, it's possible to traverse the edge in both directions. More... | |
class | Vertex |
A vertex of a graph. It stores user information, an optional name, and keeps an internal unique Id. This class does not enforce to choose a unique name. More... | |
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... | |
template<typename V , typename E > | |
using | DirectedGraph = Graph< V, E, DirectedEdge< E > > |
using | EdgeId = uint64_t |
The unique Id for an edge. More... | |
using | EdgeId_S = std::set< EdgeId > |
template<typename EdgeType > | |
using | EdgeRef_M = std::map< EdgeId, std::reference_wrapper< const EdgeType > > |
template<typename V , typename E > | |
using | UndirectedGraph = Graph< V, E, UndirectedEdge< E > > |
using | VertexId = uint64_t |
The unique Id of each vertex. More... | |
using | VertexId_P = std::pair< VertexId, VertexId > |
template<typename V > | |
using | VertexRef_M = std::map< VertexId, std::reference_wrapper< const Vertex< V > >> |
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 VV , typename EE > | |
std::ostream & | operator<< (std::ostream &_out, const Graph< VV, EE, DirectedEdge< EE >> &_g) |
Partial template specification for directed edges. More... | |
template<typename VV , typename EE > | |
std::ostream & | operator<< (std::ostream &_out, const Graph< VV, EE, UndirectedEdge< EE >> &_g) |
Partial template specification for undirected edges. 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... | |
Variables | |
static const VertexId | kNullId = MAX_UI64 |
Represents an invalid Id. More... | |
Typedef Documentation
◆ CostInfo
Used in Dijkstra. For a given source vertex, this pair represents the cost (first element) to reach a destination vertex (second element).
◆ DirectedGraph
using DirectedGraph = Graph<V, E, DirectedEdge<E> > |
◆ EdgeId
The unique Id for an edge.
◆ EdgeId_S
◆ EdgeRef_M
using EdgeRef_M = std::map<EdgeId, std::reference_wrapper<const EdgeType> > |
◆ UndirectedGraph
using UndirectedGraph = Graph<V, E, UndirectedEdge<E> > |
◆ VertexId
The unique Id of each vertex.
◆ VertexId_P
using VertexId_P = std::pair<VertexId, VertexId> |
◆ VertexRef_M
using VertexRef_M = std::map<VertexId, std::reference_wrapper<const Vertex<V> >> |
Function Documentation
◆ BreadthFirstSort()
std::vector<VertexId> gz::math::graph::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.
- Parameters
-
[in] _graph A graph. [in] _from The starting vertex.
- Returns
- The vector of vertices Ids traversed in a breadth first manner.
References Graph< V, E, EdgeType >::AddEdge(), Graph< V, E, EdgeType >::AddVertex(), Graph< V, E, EdgeType >::AdjacentsFrom(), Graph< V, E, EdgeType >::Edges(), list< T >::empty(), list< T >::front(), list< T >::pop_front(), list< T >::push_back(), vector< T >::push_back(), Graph< V, E, EdgeType >::VertexFromId(), and Graph< V, E, EdgeType >::Vertices().
Referenced by ConnectedComponents().
◆ ConnectedComponents()
std::vector<UndirectedGraph<V, E> > gz::math::graph::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.
- Parameters
-
[in] _graph A graph.
- Returns
- A vector of graphs. Each element of the graph is a component (subgraph) of the original graph.
References BreadthFirstSort(), Graph< V, E, EdgeType >::Edges(), map< K, T >::end(), map< K, T >::find(), and Graph< V, E, EdgeType >::Vertices().
◆ DepthFirstSort()
std::vector<VertexId> gz::math::graph::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.
- Parameters
-
[in] _graph A graph. [in] _from The starting vertex.
- Returns
- The vector of vertices Ids visited in a depth first manner.
References Graph< V, E, EdgeType >::AddEdge(), Graph< V, E, EdgeType >::AddVertex(), Graph< V, E, EdgeType >::AdjacentsFrom(), Graph< V, E, EdgeType >::Edges(), vector< T >::push_back(), stack< T >::top(), Graph< V, E, EdgeType >::VertexFromId(), and Graph< V, E, EdgeType >::Vertices().
◆ Dijkstra()
std::map<VertexId, CostInfo> gz::math::graph::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.
- Parameters
-
[in] _graph A graph. [in] _from The starting vertex. [in] _to Optional destination vertex.
- Returns
- A map where the keys are the destination vertices. For each destination, the value is another pair, where the key is the shortest cost from the origin vertex. The value is the previous neighbor Id in the shortest path. Note: In the case of providing a destination vertex, only the entry in the map with key = _to should be used. The rest of the map may contain incomplete information. If you want all shortest paths to all other vertices, please remove the destination vertex. If the source or destination vertex don't exist, the function will return an empty map.
E.g.: Given the following undirected graph, g, with five vertices:
(6) | 0-------1 | | /|\ | | / | \(5) | | (2)/ | \ | | / | 2 | (1)| / (2)| / | | / | /(5) | |/ |/ | 3-------4 | (1) |
This is the resut of Dijkstra(g, 0):
This is the result of Dijkstra(g, 0, 3):
References std::endl(), Graph< V, E, EdgeType >::IncidentsFrom(), kNullId, std::make_pair(), gz::math::MAX_D, and Graph< V, E, EdgeType >::Vertices().
◆ operator<<() [1/2]
std::ostream& gz::math::graph::operator<< | ( | std::ostream & | _out, |
const Graph< VV, EE, DirectedEdge< EE >> & | _g | ||
) |
Partial template specification for directed edges.
References std::endl().
◆ operator<<() [2/2]
std::ostream& gz::math::graph::operator<< | ( | std::ostream & | _out, |
const Graph< VV, EE, UndirectedEdge< EE >> & | _g | ||
) |
Partial template specification for undirected edges.
References std::endl().
◆ ToUndirectedGraph()
UndirectedGraph<V, E> gz::math::graph::ToUndirectedGraph | ( | const DirectedGraph< V, E > & | _graph | ) |
Copy a DirectedGraph to an UndirectedGraph with the same vertices and edges.
- Parameters
-
[in] _graph A directed graph.
- Returns
- An undirected graph with the same vertices and edges as the original graph.
References Graph< V, E, EdgeType >::Edges(), vector< T >::push_back(), and Graph< V, E, EdgeType >::Vertices().
Variable Documentation
◆ kNullId
Represents an invalid Id.
Referenced by Graph< V, E, EdgeType >::AddEdge(), Graph< V, E, EdgeType >::AddVertex(), Graph< V, E, EdgeType >::AdjacentsFrom(), Dijkstra(), UndirectedEdge< E >::From(), DirectedEdge< E >::From(), Graph< V, E, EdgeType >::IncidentsFrom(), Graph< V, E, EdgeType >::IncidentsTo(), Graph< V, E, EdgeType >::LinkEdge(), Graph< V, E, EdgeType >::RemoveEdge(), DirectedEdge< E >::To(), Edge< E >::Valid(), Vertex< V >::Valid(), and Edge< E >::Vertices().