mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
errorgraph.h
1#pragma once
2
3#include <string>
4#include <optional>
5#include <variant>
6#include <vector>
7#include <memory>
8#include <algorithm>
9
10#include <rclcpp/time.hpp>
11#include "rclcpp/clock.hpp"
12
13#include <mrs_lib/errorgraph/node_id.h>
14
15#include <mrs_msgs/msg/errorgraph_error.hpp>
16#include <mrs_msgs/msg/errorgraph_element.hpp>
17
18namespace mrs_lib
19{
20 namespace errorgraph
21 {
22 using errorgraph_error_msg_t = mrs_msgs::msg::ErrorgraphError;
23 using errorgraph_element_msg_t = mrs_msgs::msg::ErrorgraphElement;
24
48 {
49 public:
54 explicit Errorgraph(rclcpp::Clock::SharedPtr clock) : clock_(clock)
55 {
56 }
57
58 /* error_t //{ */
59
66 struct error_t
67 {
68 rclcpp::Time stamp;
69 std::string type;
70 std::optional<std::string> waited_for_topic;
71 std::optional<node_id_t> waited_for_node;
72
74 inline bool is_waiting_for() const
75 {
77 }
78
80 inline bool is_waiting_for_topic() const
81 {
82 return type == errorgraph_error_msg_t::TYPE_WAITING_FOR_TOPIC;
83 }
84
86 inline bool is_waiting_for_node() const
87 {
88 return type == errorgraph_error_msg_t::TYPE_WAITING_FOR_NODE;
89 }
90
92 inline bool is_waiting_for(const std::string& topic) const
93 {
94 return type == errorgraph_error_msg_t::TYPE_WAITING_FOR_TOPIC && waited_for_topic.has_value() && waited_for_topic.value() == topic;
95 }
96
98 inline bool is_waiting_for(const node_id_t& node_id) const
99 {
100 return type == errorgraph_error_msg_t::TYPE_WAITING_FOR_NODE && waited_for_node.has_value() && waited_for_node.value() == node_id;
101 }
102
104 inline bool is_no_error() const
105 {
106 return type == errorgraph_error_msg_t::TYPE_NO_ERROR;
107 }
108
110 error_t(const errorgraph_error_msg_t& msg) : type(msg.type)
111 {
112 if (msg.type == errorgraph_error_msg_t::TYPE_WAITING_FOR_NODE)
113 waited_for_node = node_id_t::from_msg(msg.waited_for_node);
114 else if (msg.type == errorgraph_error_msg_t::TYPE_WAITING_FOR_TOPIC)
115 {
116 waited_for_topic = msg.waited_for_topic;
117 if (!msg.waited_for_node.node.empty() || !msg.waited_for_node.component.empty())
118 waited_for_node = node_id_t::from_msg(msg.waited_for_node);
119 }
120 stamp = msg.stamp;
121 }
122
124 errorgraph_error_msg_t to_msg() const
125 {
126 errorgraph_error_msg_t ret;
127 ret.stamp = stamp;
128 ret.type = type;
129 if (waited_for_topic.has_value())
130 ret.waited_for_topic = waited_for_topic.value();
131 if (waited_for_node.has_value())
132 ret.waited_for_node = waited_for_node.value().to_msg();
133 return ret;
134 }
135 };
136
137 //}
138
139 /* node_info_t //{ */
140
148 {
150 std::vector<error_t> errors;
151 rclcpp::Time stamp;
153
155 errorgraph_element_msg_t to_msg() const;
156 };
157
158 //}
159
160 /* topic_info_t //{ */
161
169 {
170 std::string topic_name;
172 rclcpp::Time stamp;
174
176 errorgraph_element_msg_t to_msg() const;
177 };
178
179 //}
180
182 using element_info_t = std::variant<node_info_t, topic_info_t>;
183
184 /* element_t //{ */
185
197 {
199 enum class type_t
200 {
201 node,
202 topic
203 };
204
205 size_t element_id;
207
208 std::string topic_name;
210
211 std::vector<error_t> errors;
212 rclcpp::Time stamp;
213 static constexpr double DEFAULT_NOT_REPORTING_DELAY_SECONDS = 3.0;
214 rclcpp::Duration not_reporting_delay = rclcpp::Duration::from_seconds(DEFAULT_NOT_REPORTING_DELAY_SECONDS);
215
216 std::vector<element_t*> parents;
217 std::vector<element_t*> children;
218 bool visited = false;
219
220 rclcpp::Clock::SharedPtr clock_;
221
223 element_t(size_t element_id, const node_id_t& source_node, rclcpp::Clock::SharedPtr clock)
224 : element_id(element_id), type(type_t::node), source_node(source_node), stamp(static_cast<int64_t>(0), clock->get_clock_type()), clock_(clock){};
225
227 element_t(size_t element_id, const std::string& topic_name, const node_id_t& source_node, rclcpp::Clock::SharedPtr clock)
229 stamp(static_cast<int64_t>(0), clock->get_clock_type()), clock_(clock){};
230
232 inline std::vector<const std::string*> waited_for_topics() const
233 {
234 std::vector<const std::string*> ret;
235 ret.reserve(errors.size());
236 for (const auto& el : errors)
237 {
238 if (el.waited_for_topic.has_value())
239 ret.push_back(&el.waited_for_topic.value());
240 }
241 return ret;
242 }
243
245 inline std::vector<const node_id_t*> waited_for_nodes() const
246 {
247 std::vector<const node_id_t*> ret;
248 ret.reserve(errors.size());
249 for (const auto& el : errors)
250 {
251 if (el.waited_for_node.has_value())
252 ret.push_back(&el.waited_for_node.value());
253 }
254 return ret;
255 }
256
258 inline bool is_waiting_for() const
259 {
260 return std::any_of(std::begin(errors), std::end(errors), [](const auto& error) { return error.is_waiting_for(); });
261 }
262
264 inline bool is_waiting_for(const node_id_t& node_id) const
265 {
266 return std::any_of(std::begin(errors), std::end(errors), [node_id](const auto& error) { return error.is_waiting_for(node_id); });
267 }
268
270 inline bool is_no_error() const
271 {
272 return !is_not_reporting() && std::all_of(std::begin(errors), std::end(errors), [](const auto& error) { return error.is_no_error(); });
273 }
274
276 inline bool is_not_reporting() const
277 {
278 return type != type_t::topic && clock_->now() - stamp > not_reporting_delay;
279 }
280
282 errorgraph_element_msg_t to_msg() const
283 {
284 errorgraph_element_msg_t ret;
285 ret.stamp = stamp;
286 ret.source_node = source_node.to_msg();
287 for (const auto& error : errors)
288 ret.errors.push_back(error.to_msg());
289 return ret;
290 }
291
293 element_info_t to_info() const;
294 };
295
296 //}
297
298 private:
299 std::vector<std::unique_ptr<element_t>> elements_;
300 bool graph_up_to_date_ = false;
301 rclcpp::Clock::SharedPtr clock_;
302
303 std::vector<element_t*> find_elements_waited_for(const element_t& by_element);
304
305 element_t* find_element_mutable(const std::string& topic_name);
306
307 element_t* find_element_mutable(const node_id_t& node_id);
308
309 void prepare_graph();
310
311 void build_graph();
312
313 std::vector<const element_t*> DFS(element_t* from, bool* loop_detected_out = nullptr);
314
315 element_t* add_new_element(const std::string& topic_name, const node_id_t& node_id = {});
316
317 element_t* add_new_element(const node_id_t& node_id);
318
319 size_t last_element_id = 0;
320
321 public:
326 void write_dot(std::ostream& os);
327
338 std::vector<element_info_t> find_dependency_roots(const node_id_t& node_id, bool* loop_detected_out = nullptr);
339
344 std::vector<element_info_t> find_error_roots();
345
350 std::vector<element_info_t> find_roots();
351
356 std::vector<element_info_t> find_leaves();
357
363 std::optional<element_info_t> find_element(const std::string& topic_name);
364
370 std::optional<element_info_t> find_element(const node_id_t& node_id);
371
382 element_info_t add_element_from_msg(const errorgraph_element_msg_t& msg);
383 };
384
385 } // namespace errorgraph
386} // namespace mrs_lib
A directed graph representing error dependencies between ROS nodes and topics.
Definition errorgraph.h:48
std::vector< element_info_t > find_roots()
Find all root elements (elements with no parents in the dependency graph).
Definition errorgraph.cpp:103
std::vector< element_info_t > find_leaves()
Find all leaf elements (elements with no children in the dependency graph).
Definition errorgraph.cpp:115
element_info_t add_element_from_msg(const errorgraph_element_msg_t &msg)
Add or update an element from a received ROS message.
Definition errorgraph.cpp:245
std::variant< node_info_t, topic_info_t > element_info_t
Type-safe variant representing either a node or topic element info.
Definition errorgraph.h:182
std::vector< element_info_t > find_error_roots()
Find all root-cause elements across the entire graph.
Definition errorgraph.cpp:91
std::vector< element_info_t > find_dependency_roots(const node_id_t &node_id, bool *loop_detected_out=nullptr)
Find the root-cause elements blocking the given node.
Definition errorgraph.cpp:10
std::optional< element_info_t > find_element(const std::string &topic_name)
Find an element by topic name.
Definition errorgraph.cpp:171
Errorgraph(rclcpp::Clock::SharedPtr clock)
Construct an empty Errorgraph.
Definition errorgraph.h:54
void write_dot(std::ostream &os)
Write the graph in Graphviz DOT format.
Definition errorgraph.cpp:295
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Internal representation of a node or topic in the error dependency graph.
Definition errorgraph.h:197
std::vector< error_t > errors
List of errors reported by this element (nodes only).
Definition errorgraph.h:211
std::string topic_name
Topic name (only meaningful if type == topic).
Definition errorgraph.h:208
element_t(size_t element_id, const node_id_t &source_node, rclcpp::Clock::SharedPtr clock)
Construct a node element.
Definition errorgraph.h:223
std::vector< const node_id_t * > waited_for_nodes() const
Returns pointers to node IDs this element is waiting for.
Definition errorgraph.h:245
errorgraph_element_msg_t to_msg() const
Convert to a ROS message.
Definition errorgraph.h:282
rclcpp::Time stamp
Last time this element was updated from a message.
Definition errorgraph.h:212
size_t element_id
Unique ID of this element within the graph.
Definition errorgraph.h:205
std::vector< element_t * > parents
Parent elements in the dependency graph.
Definition errorgraph.h:216
type_t type
Whether this is a node or topic element.
Definition errorgraph.h:206
element_t(size_t element_id, const std::string &topic_name, const node_id_t &source_node, rclcpp::Clock::SharedPtr clock)
Construct a topic element.
Definition errorgraph.h:227
bool is_waiting_for(const node_id_t &node_id) const
Returns true if this element is waiting for the given node.
Definition errorgraph.h:264
std::vector< element_t * > children
Child elements in the dependency graph.
Definition errorgraph.h:217
bool is_not_reporting() const
Returns true if this node element has stopped reporting (stale).
Definition errorgraph.h:276
std::vector< const std::string * > waited_for_topics() const
Returns pointers to topic names this element is waiting for.
Definition errorgraph.h:232
bool visited
Visited flag used during graph traversal.
Definition errorgraph.h:218
node_id_t source_node
Source node ID, or expected publisher for a topic.
Definition errorgraph.h:209
element_info_t to_info() const
Convert to a public element_info_t variant.
Definition errorgraph.cpp:262
bool is_waiting_for() const
Returns true if this element has any dependency errors.
Definition errorgraph.h:258
type_t
Whether this element represents a node or a topic.
Definition errorgraph.h:200
bool is_no_error() const
Returns true if this element has no errors and is actively reporting.
Definition errorgraph.h:270
Represents a single error reported by a node.
Definition errorgraph.h:67
bool is_waiting_for(const std::string &topic) const
Returns true if this error is waiting for the given topic.
Definition errorgraph.h:92
rclcpp::Time stamp
Timestamp when the error was reported.
Definition errorgraph.h:68
errorgraph_error_msg_t to_msg() const
Convert to a ROS message.
Definition errorgraph.h:124
error_t(const errorgraph_error_msg_t &msg)
Construct from a ROS message.
Definition errorgraph.h:110
bool is_no_error() const
Returns true if this represents a "no error" state.
Definition errorgraph.h:104
bool is_waiting_for(const node_id_t &node_id) const
Returns true if this error is waiting for the given node.
Definition errorgraph.h:98
bool is_waiting_for_node() const
Returns true if this error is waiting for a node.
Definition errorgraph.h:86
std::optional< node_id_t > waited_for_node
Node ID if this is a "waiting for node" error.
Definition errorgraph.h:71
bool is_waiting_for() const
Returns true if this error indicates a dependency (waiting for a topic or node).
Definition errorgraph.h:74
std::string type
Error type string (see ErrorgraphError message constants).
Definition errorgraph.h:69
std::optional< std::string > waited_for_topic
Topic name if this is a "waiting for topic" error.
Definition errorgraph.h:70
bool is_waiting_for_topic() const
Returns true if this error is waiting for a topic.
Definition errorgraph.h:80
Public view of a node element, returned by query methods.
Definition errorgraph.h:148
rclcpp::Time stamp
Last time this element was updated.
Definition errorgraph.h:151
std::vector< error_t > errors
List of errors reported by this node.
Definition errorgraph.h:150
bool not_reporting
Whether this node has stopped reporting (stale).
Definition errorgraph.h:152
errorgraph_element_msg_t to_msg() const
Convert to a ROS message.
Definition errorgraph.cpp:270
node_id_t source_node
Node ID of this element.
Definition errorgraph.h:149
Public view of a topic element, returned by query methods.
Definition errorgraph.h:169
errorgraph_element_msg_t to_msg() const
Convert to a ROS message.
Definition errorgraph.cpp:280
bool not_reporting
Whether this topic's publisher has stopped reporting.
Definition errorgraph.h:173
rclcpp::Time stamp
Last time this element was updated.
Definition errorgraph.h:172
std::string topic_name
Topic name.
Definition errorgraph.h:170
node_id_t source_node
Expected publisher node for this topic.
Definition errorgraph.h:171
Identifies a specific component within a ROS node for error reporting.
Definition node_id.h:21
errorgraph_node_id_msg_t to_msg() const
Convert to a ROS message.
Definition node_id.h:41
static node_id_t from_msg(const errorgraph_node_id_msg_t &msg)
Construct from a ROS message.
Definition node_id.h:32