3 #include <boost/graph/graphml.hpp>
4 #include <boost/graph/graphviz.hpp>
23 template <
class Graph>
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 <<
"\"]";
39 template <
class Graph>
43 template <
class VertexOrEdge>
44 void operator()(std::ostream& out,
const VertexOrEdge& v)
const {
49 out <<
"\" weight=\"" << (*graph_)[v].routingCost;
51 out <<
"\" routingCostId=\"" << (*graph_)[v].costId <<
"\"]";
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()) {
68 if (!file.is_open()) {
74 boost::filtered_graph<G, E, V> fg(g, edgeFilter, vertexFilter);
75 boost::write_graphviz(file, fg, vertexWriter, edgeWriter);
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()) {
102 if (!file.is_open()) {
106 boost::filtered_graph<G, EdgeCostFilter<G>> filteredGraph(g, eFilter, vFilter);
112 boost::dynamic_properties dp;
113 dp.property(
"info", pmId);
114 dp.property(
"relation", pmRelation);
115 dp.property(
"routingCost", pmRoutingCosts);
117 boost::write_graphml(file, filteredGraph, dp,
false);
125 template <
typename G>