10#include <rclcpp/time.hpp>
11#include "rclcpp/clock.hpp"
13#include <mrs_lib/errorgraph/node_id.h>
15#include <mrs_msgs/msg/errorgraph_error.hpp>
16#include <mrs_msgs/msg/errorgraph_element.hpp>
22 using errorgraph_error_msg_t = mrs_msgs::msg::ErrorgraphError;
23 using errorgraph_element_msg_t = mrs_msgs::msg::ErrorgraphElement;
54 explicit Errorgraph(rclcpp::Clock::SharedPtr clock) : clock_(clock)
82 return type == errorgraph_error_msg_t::TYPE_WAITING_FOR_TOPIC;
88 return type == errorgraph_error_msg_t::TYPE_WAITING_FOR_NODE;
106 return type == errorgraph_error_msg_t::TYPE_NO_ERROR;
112 if (msg.type == errorgraph_error_msg_t::TYPE_WAITING_FOR_NODE)
114 else if (msg.type == errorgraph_error_msg_t::TYPE_WAITING_FOR_TOPIC)
117 if (!msg.waited_for_node.node.empty() || !msg.waited_for_node.component.empty())
126 errorgraph_error_msg_t ret;
155 errorgraph_element_msg_t
to_msg()
const;
176 errorgraph_element_msg_t
to_msg()
const;
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);
220 rclcpp::Clock::SharedPtr clock_;
229 stamp(static_cast<int64_t>(0), clock->get_clock_type()), clock_(clock){};
234 std::vector<const std::string*> ret;
235 ret.reserve(
errors.size());
236 for (
const auto& el :
errors)
238 if (el.waited_for_topic.has_value())
239 ret.push_back(&el.waited_for_topic.value());
247 std::vector<const node_id_t*> ret;
248 ret.reserve(
errors.size());
249 for (
const auto& el :
errors)
251 if (el.waited_for_node.has_value())
252 ret.push_back(&el.waited_for_node.value());
260 return std::any_of(std::begin(
errors), std::end(
errors), [](
const auto& error) {
return error.is_waiting_for(); });
266 return std::any_of(std::begin(
errors), std::end(
errors), [node_id](
const auto& error) {
return error.is_waiting_for(node_id); });
278 return type != type_t::topic && clock_->now() -
stamp > not_reporting_delay;
284 errorgraph_element_msg_t ret;
287 for (
const auto& error :
errors)
288 ret.errors.push_back(error.to_msg());
299 std::vector<std::unique_ptr<element_t>> elements_;
300 bool graph_up_to_date_ =
false;
301 rclcpp::Clock::SharedPtr clock_;
303 std::vector<element_t*> find_elements_waited_for(
const element_t& by_element);
305 element_t* find_element_mutable(
const std::string& topic_name);
307 element_t* find_element_mutable(
const node_id_t& node_id);
309 void prepare_graph();
313 std::vector<const element_t*> DFS(element_t* from,
bool* loop_detected_out =
nullptr);
315 element_t* add_new_element(
const std::string& topic_name,
const node_id_t& node_id = {});
317 element_t* add_new_element(
const node_id_t& node_id);
319 size_t last_element_id = 0;
338 std::vector<element_info_t>
find_dependency_roots(
const node_id_t& node_id,
bool* loop_detected_out =
nullptr);
363 std::optional<element_info_t>
find_element(
const std::string& topic_name);
370 std::optional<element_info_t>
find_element(
const node_id_t& node_id);
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