sml_transition_graph.h
Go to the documentation of this file.
1 // Copyright 2021 PickNik Inc.
2 //
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 //
6 // * Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 //
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 //
13 // * Neither the name of the PickNik Inc. nor the names of its
14 // contributors may be used to endorse or promote products derived from
15 // this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 
29 /*
30  * Desc: Class to generate SML diagrams using boost.Graph library
31  */
32 
33 #pragma once
34 
35 #include <string>
36 // [boost].SML
37 #include <boost_sml/sml.hpp>
38 // Boost.Graph
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>
43 
45 
46 // A bundle for the state's name see
47 // https://www.boost.org/doc/libs/1_49_0/libs/graph/doc/bundles.html
48 struct State {
49  std::string name;
50 };
51 using graph_t =
52  boost::adjacency_list<boost::vecS, boost::vecS, boost::directedS, State>;
53 
54 class SmlTransitionGraph : public graph_t {
55  public:
56  using edge_t = std::pair<std::string, std::string>;
57  const vertex_descriptor NIL = std::numeric_limits<vertex_descriptor>::max();
58 
59  template <class SM>
60  SmlTransitionGraph(const SM& sm) {
61  construct_graph(sm);
62  }
63  void write_graphiz(std::ostream& out = std::cout) const {
64  boost::write_graphviz(
65  out, *this, boost::make_label_writer(boost::get(&State::name, *this)));
66  }
67 
68  void write_all_reachable_states(const vertex_descriptor& start_vertex,
69  std::ostream& out = std::cout) {
70  const auto predecessors = find_predecessors(start_vertex);
71  write_graphviz_predecessors(out, predecessors);
72  }
73 
74  // TODO: write all paths
75  // https://github.com/networkx/networkx/blob/master/networkx/algorithms/simple_paths.py
76  void write_path_between_two_states(const vertex_descriptor& start_vertex,
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);
81  }
82 
83  std::vector<vertex_descriptor> find_path(
84  const vertex_descriptor& start_vertex,
85  const vertex_descriptor& goal_vertex) {
86  if (start_vertex == goal_vertex) return {};
87 
88  const auto predecessors = find_predecessors(start_vertex);
89 
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);
94 
95  return path;
96  }
97 
98  std::vector<vertex_descriptor> find_predecessors(
99  const vertex_descriptor& start_vertex) {
100  std::vector<vertex_descriptor> predecessors(boost::num_vertices(*this),
101  NIL);
102  boost::breadth_first_search(
103  *this, start_vertex,
104  boost::visitor(boost::make_bfs_visitor(boost::record_predecessors(
105  &predecessors[0], boost::on_tree_edge()))));
106  return predecessors;
107  }
108 
109  vertex_descriptor get_vertex_index(const std::string& vertex_name) const {
110  return vertex_name_to_descriptor_map_.at(vertex_name);
111  }
112  std::string get_vertex_name(const vertex_descriptor& vertex_index) const {
113  return (*this)[vertex_index].name;
114  }
115 
116  private:
117  template <class T>
118  void construct_edge(std::vector<edge_t>& edges) noexcept {
119  auto src_state =
120  std::string{boost::sml::aux::string<typename T::src_state>{}.c_str()};
121  auto dst_state =
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});
124  // Check if dst_state starts with prefix
125  if (dst_state.rfind("boost::sml::", 0) == 0) return;
126  edges.push_back({src_state, dst_state});
127  }
128 
129  template <template <class...> class T, class... Ts>
130  void construct_edges_impl(const T<Ts...>&,
131  std::vector<edge_t>& edges) noexcept {
132  int _[]{0, (construct_edge<Ts>(edges), 0)...};
133  (void)_;
134  }
135 
136  template <class SM>
137  std::vector<edge_t> construct_edges(const SM& /* sm */) noexcept {
138  std::vector<edge_t> edges;
139  construct_edges_impl(typename SM::transitions{}, edges);
140  return edges;
141  }
142 
143  template <class SM>
144  void construct_graph(const SM& sm) noexcept {
145  auto edges = construct_edges(sm);
146  // Create unique vertices
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});
153  }
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);
157  }
158 
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\"";
170  else
171  out << ", color=\"grey\"";
172  out << "];\n";
173  }
174  out << "}\n";
175  }
176 
177  void write_graphviz_path(std::ostream& out,
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\"";
189  else
190  out << ", color=\"grey\"";
191  out << "];\n";
192  }
193  out << "}\n";
194  }
195 
196  std::unordered_map<std::string, vertex_descriptor>
198 };
199 } // namespace sml_transition_graph
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_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


boost_sml
Author(s): boost-experimental (https://github.com/boost-experimental)
autogenerated on Thu Jan 26 2023 03:14:02