![]() |
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
Internal representation of a node or topic in the error dependency graph. More...
#include <errorgraph.h>
Collaboration diagram for mrs_lib::errorgraph::Errorgraph::element_t:Public Types | |
| enum class | type_t { node , topic } |
| Whether this element represents a node or a topic. | |
Public Member Functions | |
| element_t (size_t element_id, const node_id_t &source_node, rclcpp::Clock::SharedPtr clock) | |
| Construct a node element. | |
| 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. | |
| std::vector< const std::string * > | waited_for_topics () const |
| Returns pointers to topic names this element is waiting for. | |
| std::vector< const node_id_t * > | waited_for_nodes () const |
| Returns pointers to node IDs this element is waiting for. | |
| bool | is_waiting_for () const |
| Returns true if this element has any dependency errors. | |
| bool | is_waiting_for (const node_id_t &node_id) const |
| Returns true if this element is waiting for the given node. | |
| bool | is_no_error () const |
| Returns true if this element has no errors and is actively reporting. | |
| bool | is_not_reporting () const |
| Returns true if this node element has stopped reporting (stale). | |
| errorgraph_element_msg_t | to_msg () const |
| Convert to a ROS message. | |
| element_info_t | to_info () const |
| Convert to a public element_info_t variant. | |
Public Attributes | |
| size_t | element_id |
| Unique ID of this element within the graph. | |
| type_t | type |
| Whether this is a node or topic element. | |
| std::string | topic_name |
| Topic name (only meaningful if type == topic). | |
| node_id_t | source_node |
| Source node ID, or expected publisher for a topic. | |
| std::vector< error_t > | errors |
| List of errors reported by this element (nodes only). | |
| rclcpp::Time | stamp |
| Last time this element was updated from a message. | |
| rclcpp::Duration | not_reporting_delay = rclcpp::Duration::from_seconds(DEFAULT_NOT_REPORTING_DELAY_SECONDS) |
| std::vector< element_t * > | parents |
| Parent elements in the dependency graph. | |
| std::vector< element_t * > | children |
| Child elements in the dependency graph. | |
| bool | visited = false |
| Visited flag used during graph traversal. | |
| rclcpp::Clock::SharedPtr | clock_ |
Static Public Attributes | |
| static constexpr double | DEFAULT_NOT_REPORTING_DELAY_SECONDS = 3.0 |
Internal representation of a node or topic in the error dependency graph.
Each element is either a ROS node (identified by node_id_t) or a topic (identified by name). Node elements carry a list of errors; topic elements serve as intermediate vertices connecting nodes in the dependency graph.