39 #include <boost/graph/adjacency_list.hpp> 40 #include <boost/graph/breadth_first_search.hpp> 41 #include <boost/graph/graph_traits.hpp> 42 #include <boost/graph/graphviz.hpp> 52 boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, State>;
56 using edge_t = std::pair<std::string, std::string>;
57 const vertex_descriptor NIL = std::numeric_limits<vertex_descriptor>::max();
64 boost::write_graphviz(
65 out, *
this, boost::make_label_writer(boost::get(&
State::name, *
this)));
69 std::ostream& out = std::cout) {
70 const auto predecessors = find_predecessors(start_vertex);
71 write_graphviz_predecessors(out, predecessors);
77 const vertex_descriptor& goal_vertex,
78 std::ostream& out = std::cout) {
79 auto path = find_path(start_vertex, goal_vertex);
80 write_graphviz_path(out, path);
84 const vertex_descriptor& start_vertex,
85 const vertex_descriptor& goal_vertex) {
86 if (start_vertex == goal_vertex)
return {};
88 const auto predecessors = find_predecessors(start_vertex);
90 std::vector<vertex_descriptor> path = {goal_vertex};
91 for (
auto current_vertex = predecessors[goal_vertex]; current_vertex != NIL;
92 current_vertex = predecessors[current_vertex])
93 path.push_back(current_vertex);
99 const vertex_descriptor& start_vertex) {
100 std::vector<vertex_descriptor> predecessors(boost::num_vertices(*
this),
102 boost::breadth_first_search(
104 boost::visitor(boost::make_bfs_visitor(boost::record_predecessors(
105 &predecessors[0], boost::on_tree_edge()))));
110 return vertex_name_to_descriptor_map_.at(vertex_name);
113 return (*
this)[vertex_index].name;
120 std::string{boost::sml::aux::string<typename T::src_state>{}.c_str()};
122 std::string{boost::sml::aux::string<typename T::dst_state>{}.c_str()};
123 if (T::initial) edges.push_back({
"sml_entry_point", src_state});
125 if (dst_state.rfind(
"boost::sml::", 0) == 0)
return;
126 edges.push_back({src_state, dst_state});
129 template <
template <
class...>
class T,
class... Ts>
131 std::vector<edge_t>& edges) noexcept {
132 int _[]{0, (construct_edge<Ts>(edges), 0)...};
138 std::vector<edge_t> edges;
139 construct_edges_impl(
typename SM::transitions{}, edges);
145 auto edges = construct_edges(sm);
147 std::unordered_set<std::string> vertices;
148 for (
const auto& edge : edges) vertices.insert({edge.first, edge.second});
149 for (
const auto& vertex : vertices) {
150 auto vertex_descriptor = boost::add_vertex(*
this);
151 (*this)[vertex_descriptor].name = vertex;
152 vertex_name_to_descriptor_map_.insert({vertex, vertex_descriptor});
154 for (
const auto& edge : edges)
155 boost::add_edge(vertex_name_to_descriptor_map_[edge.first],
156 vertex_name_to_descriptor_map_[edge.second], *
this);
160 std::ostream& out,
const std::vector<vertex_descriptor>& predecessors) {
161 out <<
"digraph G {\n";
162 edge_iterator ei, ei_end;
163 for (boost::tie(ei, ei_end) = edges(*
this); ei != ei_end; ++ei) {
164 edge_descriptor e = *ei;
165 vertex_descriptor u = boost::source(e, *
this),
166 v = boost::target(e, *
this);
167 out << (*this)[u].name <<
" -> " << (*this)[v].name <<
"[label=\" \"";
168 if (predecessors[v] == u)
169 out <<
", color=\"black\"";
171 out <<
", color=\"grey\"";
178 const std::vector<vertex_descriptor>& path) {
179 out <<
"digraph G {\n";
180 edge_iterator ei, ei_end;
181 for (boost::tie(ei, ei_end) = edges(*
this); ei != ei_end; ++ei) {
182 edge_descriptor e = *ei;
183 vertex_descriptor u = boost::source(e, *
this),
184 v = boost::target(e, *
this);
185 out << (*this)[u].name <<
" -> " << (*this)[v].name <<
"[label=\" \"";
186 if (std::find(path.cbegin(), path.cend(), u) != path.end() &&
187 std::find(path.cbegin(), path.cend(), v) != path.end())
188 out <<
", color=\"black\"";
190 out <<
", color=\"grey\"";
196 std::unordered_map<std::string, vertex_descriptor>
std::vector< edge_t > construct_edges(const SM &) noexcept
void write_path_between_two_states(const vertex_descriptor &start_vertex, const vertex_descriptor &goal_vertex, std::ostream &out=std::cout)
std::vector< vertex_descriptor > find_predecessors(const vertex_descriptor &start_vertex)
void write_graphviz_predecessors(std::ostream &out, const std::vector< vertex_descriptor > &predecessors)
void write_graphviz_path(std::ostream &out, const std::vector< vertex_descriptor > &path)
void construct_graph(const SM &sm) noexcept
void construct_edge(std::vector< edge_t > &edges) noexcept
void write_graphiz(std::ostream &out=std::cout) const
vertex_descriptor get_vertex_index(const std::string &vertex_name) const
std::string get_vertex_name(const vertex_descriptor &vertex_index) const
std::unordered_map< std::string, vertex_descriptor > vertex_name_to_descriptor_map_
std::vector< vertex_descriptor > find_path(const vertex_descriptor &start_vertex, const vertex_descriptor &goal_vertex)
void construct_edges_impl(const T< Ts... > &, std::vector< edge_t > &edges) noexcept
boost::adjacency_list< boost::vecS, boost::vecS, boost::directedS, State > graph_t
void write_all_reachable_states(const vertex_descriptor &start_vertex, std::ostream &out=std::cout)
std::pair< std::string, std::string > edge_t
SmlTransitionGraph(const SM &sm)