RoutingGraphVisualization.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <boost/graph/graphml.hpp>
4 #include <boost/graph/graphviz.hpp>
5 #include <iostream>
6 
10 
11 namespace lanelet {
12 
13 // This one needs to be in this namepace. Otherwise it's not found.
14 inline std::istream& operator>>(std::istream& is, ConstLaneletOrArea& /*r*/) { return is; }
15 
16 namespace routing {
17 inline std::ostream& operator<<(std::ostream& os, const RelationType& r) { return os << relationToString(r); }
18 inline std::istream& operator>>(std::istream& is, const RelationType& /*r*/) { return is; }
19 
20 namespace internal {
21 
23 template <class Graph>
25  public:
26  explicit VertexWriterGraphViz(const Graph* g) : graph_(g) {}
27  template <class VertexOrEdge>
28  void operator()(std::ostream& out, const VertexOrEdge& v) const {
29  const Id id{(*graph_)[v].laneletOrArea.id()};
30  out << "[label=\"" << id << "\" lanelet=\"" << id << "\"]";
31  }
32 
33  private:
34  const Graph* graph_;
35 };
36 
39 template <class Graph>
41  public:
42  explicit EdgeWriterGraphViz(const Graph* g) : graph_(g) {}
43  template <class VertexOrEdge>
44  void operator()(std::ostream& out, const VertexOrEdge& v) const {
45  const RelationType relation{(*graph_)[v].relation};
46  out << "[label=\"" << relationToString(relation) << "\" color=\"" << relationToColor(relation);
47  if (relation != RelationType::AdjacentLeft && relation != RelationType::AdjacentRight &&
48  relation != RelationType::Conflicting) {
49  out << "\" weight=\"" << (*graph_)[v].routingCost;
50  }
51  out << "\" routingCostId=\"" << (*graph_)[v].costId << "\"]";
52  }
53 
54  private:
55  const Graph* graph_;
56 };
57 
63 template <typename G, typename E = boost::keep_all, typename V = boost::keep_all>
64 inline void exportGraphVizImpl(const std::string& filename, const G& g, E edgeFilter = boost::keep_all(),
65  V vertexFilter = boost::keep_all()) {
66  std::ofstream file;
67  file.open(filename);
68  if (!file.is_open()) {
69  throw lanelet::ExportError("Could not open file at " + filename + ".");
70  }
71 
72  VertexWriterGraphViz<G> vertexWriter(&g);
73  EdgeWriterGraphViz<G> edgeWriter(&g);
74  boost::filtered_graph<G, E, V> fg(g, edgeFilter, vertexFilter);
75  boost::write_graphviz(file, fg, vertexWriter, edgeWriter);
76 
77  file.close();
78 }
79 
85 template <typename G>
86 inline void exportGraphVizImpl(const std::string& filename, const G& g, const RelationType& relationTypes,
87  RoutingCostId routingCostId = 0) {
88  auto edgeFilter = EdgeCostFilter<G>(g, routingCostId, relationTypes);
89  exportGraphVizImpl(filename, g, edgeFilter);
90 }
91 
97 template <typename G, typename E = boost::keep_all, typename V = boost::keep_all>
98 inline void exportGraphMLImpl(const std::string& filename, const G& g, E eFilter = boost::keep_all(),
99  V vFilter = boost::keep_all()) {
100  std::ofstream file;
101  file.open(filename);
102  if (!file.is_open()) {
103  throw lanelet::ExportError("Could not open file at " + filename + ".");
104  }
105 
106  boost::filtered_graph<G, EdgeCostFilter<G>> filteredGraph(g, eFilter, vFilter);
107 
108  auto pmId = boost::get(&VertexInfo::laneletOrArea, filteredGraph); // NOLINT
109  auto pmRelation = boost::get(&EdgeInfo::relation, filteredGraph);
110  auto pmRoutingCosts = boost::get(&EdgeInfo::routingCost, filteredGraph);
111 
112  boost::dynamic_properties dp;
113  dp.property("info", pmId);
114  dp.property("relation", pmRelation);
115  dp.property("routingCost", pmRoutingCosts);
116 
117  boost::write_graphml(file, filteredGraph, dp, false);
118 }
119 
125 template <typename G>
126 inline void exportGraphMLImpl(const std::string& filename, const G& g, const RelationType& relationTypes,
127  RoutingCostId routingCostId = 0) {
128  auto edgeFilter = EdgeCostFilter<G>(g, routingCostId, relationTypes);
129  exportGraphMLImpl(filename, g, edgeFilter);
130 }
131 } // namespace internal
132 } // namespace routing
133 } // namespace lanelet
lanelet::routing::internal::exportGraphVizImpl
void exportGraphVizImpl(const std::string &filename, const G &g, E edgeFilter=boost::keep_all(), V vertexFilter=boost::keep_all())
Implementation of graphViz export function.
Definition: RoutingGraphVisualization.h:64
lanelet::routing::internal::EdgeWriterGraphViz
Internal edge writer for graphViz file export. Includes label, color and if existent routing cost (as...
Definition: RoutingGraphVisualization.h:40
lanelet
lanelet::routing::operator>>
std::istream & operator>>(std::istream &is, const RelationType &)
Definition: RoutingGraphVisualization.h:18
lanelet::routing::relationToString
std::string relationToString(RelationType type)
Definition: Forward.h:83
lanelet::ConstLaneletOrArea
lanelet::routing::internal::EdgeInfo::routingCost
double routingCost
Calculcated routing cost. Infinity if not routable.
Definition: Graph.h:37
lanelet::routing::internal::EdgeCostFilter
An internal edge filter to get a filtered view on the graph.
Definition: Graph.h:49
lanelet::Id
int64_t Id
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
lanelet::routing::relationToColor
std::string relationToColor(RelationType type)
Definition: Forward.h:105
lanelet::routing::internal::EdgeWriterGraphViz::operator()
void operator()(std::ostream &out, const VertexOrEdge &v) const
Definition: RoutingGraphVisualization.h:44
lanelet::routing::internal::EdgeWriterGraphViz::graph_
const Graph * graph_
Definition: RoutingGraphVisualization.h:55
lanelet::operator>>
std::istream & operator>>(std::istream &is, ConstLaneletOrArea &)
Definition: RoutingGraphVisualization.h:14
lanelet::routing::internal::VertexInfo::laneletOrArea
ConstLaneletOrArea laneletOrArea
Definition: Graph.h:23
lanelet::ExportError
Thrown when an export to the provided file(name) cannot be done.
Definition: Exceptions.h:11
lanelet::routing::operator<<
std::ostream & operator<<(std::ostream &os, const RelationType &r)
Definition: RoutingGraphVisualization.h:17
lanelet::routing::internal::get
SparseColorMap::value_type get(const SparseColorMap &map, LaneletVertexId key)
Definition: GraphUtils.h:304
lanelet::routing::RelationType::Conflicting
@ Conflicting
Unreachable but with overlapping shape.
lanelet::routing::internal::Graph
Manages the actual routing graph and provieds different views on the edges (lazily computed)
Definition: Forward.h:17
lanelet::routing::internal::exportGraphMLImpl
void exportGraphMLImpl(const std::string &filename, const G &g, E eFilter=boost::keep_all(), V vFilter=boost::keep_all())
Implementation of graphML export function.
Definition: RoutingGraphVisualization.h:98
lanelet::routing::RoutingCostId
uint16_t RoutingCostId
Definition: Forward.h:44
lanelet::routing::internal::EdgeWriterGraphViz::EdgeWriterGraphViz
EdgeWriterGraphViz(const Graph *g)
Definition: RoutingGraphVisualization.h:42
Graph.h
lanelet::routing::RelationType::AdjacentLeft
@ AdjacentLeft
directly adjacent, unreachable left neighbor
lanelet::routing::internal::VertexWriterGraphViz
Internal vertex writer for graphViz file export.
Definition: RoutingGraphVisualization.h:24
lanelet::routing::internal::VertexWriterGraphViz::operator()
void operator()(std::ostream &out, const VertexOrEdge &v) const
Definition: RoutingGraphVisualization.h:28
lanelet::routing::RelationType::AdjacentRight
@ AdjacentRight
directly adjacent, unreachable right neighbor
lanelet::routing::internal::EdgeInfo::relation
RelationType relation
Relation between the two lanelets. E.g. SUCCESSOR or CONFLICTING.
Definition: Graph.h:39
lanelet::routing::internal::VertexWriterGraphViz::graph_
const Graph * graph_
Definition: RoutingGraphVisualization.h:34
Forward.h
lanelet::routing::internal::VertexWriterGraphViz::VertexWriterGraphViz
VertexWriterGraphViz(const Graph *g)
Definition: RoutingGraphVisualization.h:26
Exceptions.h


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49