A helper class for aggregating and publishing errors to the Errorgraph. Report errors preventing your node from functioning properly using the respective methods. These are aggregated and periodically published by this class. After publishing, the list of errors is cleared, so take care when setting the publish_period.
More...
#include <error_publisher.h>
|
|
using | error_id_t = uint16_t |
| | Type of the ID used to avoid duplication of errors when using addGeneralError.
|
| |
|
| | ErrorPublisher (const rclcpp::Node::SharedPtr node, const rclcpp::Clock::SharedPtr clock, const std::string &node_name, const std::string &component_name, const rclcpp::Rate &publish_period=rclcpp::Rate(1.0)) |
| | The main constructor.
|
| |
| void | flushAndShutdown () |
| | Publishes all aggregated errors and calls rclcpp::shutdown().
|
| |
| void | addGeneralError (const error_id_t id, const std::string &description) |
| | Add a custom error to the list of aggregated errors to be published in the next period. This method uses the id to distinguish between different error types and avoid error duplication. If an element with the same id is found in the list of currently aggregated errors, it will be replaced by the new one provided. Otherwise, a new error will be added to the list.
|
| |
template<typename enum_T >
requires (std::is_enum_v<enum_T> && sizeof(std::underlying_type_t<enum_T>) <= sizeof(error_id_t)) |
| void | addGeneralError (const enum_T id, const std::string &description) |
| | A convenience overload for custom enumeration types. This overload just casts the id parameter to the error_id_t type so that you can call it with your own enumeration type more easily without casting it yourself.
|
| |
| void | addOneshotError (const std::string &description) |
| | Add an error that only appears once. This overload assumes that the error is unique, so it cannot be duplicate and doesn't need an identifier. Useful for errors during initialization that lead to termination of the node anyways.
|
| |
| void | addWaitingForNodeError (const node_id_t &node_id) |
| | Add a special error type waiting_for_node. Use this whenever your node is blocked because it waits for some kind of input from another node, such as a transformation, messages, a service, etc. This helps construct the Errorgraph and decide which errors are the roots problems blocking the system. If you don't know the component of the node for the node_id, use main.
|
| |
| void | addWaitingForTopicError (const std::string &topic_name) |
| | Add a special error type waiting_for_topic. You should prioritize using the addWaitingForNodeError() method if you know the node that should publish this topic to provide better information to the Errorgraph. Use this method if the node publishing the topic is unknown or can change.
|
| |
A helper class for aggregating and publishing errors to the Errorgraph. Report errors preventing your node from functioning properly using the respective methods. These are aggregated and periodically published by this class. After publishing, the list of errors is cleared, so take care when setting the publish_period.
◆ ErrorPublisher()
| mrs_lib::errorgraph::ErrorPublisher::ErrorPublisher |
( |
const rclcpp::Node::SharedPtr |
node, |
|
|
const rclcpp::Clock::SharedPtr |
clock, |
|
|
const std::string & |
node_name, |
|
|
const std::string & |
component_name, |
|
|
const rclcpp::Rate & |
publish_period = rclcpp::Rate(1.0) |
|
) |
| |
The main constructor.
- Parameters
-
| node | The ROS2 node used for publisher advertisement and timer registration. |
| clock | The clock used for timestamping the published error messages. |
| node_name | Name of the ROS node used for filling out the node_id in the published error messages. |
| component_name | Name of the component used for filling out the node_id in the published error messages. |
| publish_period | How often will the aggregated errors be published. |
◆ addGeneralError() [1/2]
template<typename enum_T >
requires (std::is_enum_v<enum_T> && sizeof(std::underlying_type_t<enum_T>) <= sizeof(
error_id_t))
| void mrs_lib::errorgraph::ErrorPublisher::addGeneralError |
( |
const enum_T |
id, |
|
|
const std::string & |
description |
|
) |
| |
|
inline |
A convenience overload for custom enumeration types. This overload just casts the id parameter to the error_id_t type so that you can call it with your own enumeration type more easily without casting it yourself.
- Parameters
-
| id | The unique identification number of this error type for this ErrorPublisher. |
| description | A short and succinct description of the error. |
◆ addGeneralError() [2/2]
| void mrs_lib::errorgraph::ErrorPublisher::addGeneralError |
( |
const error_id_t |
id, |
|
|
const std::string & |
description |
|
) |
| |
Add a custom error to the list of aggregated errors to be published in the next period. This method uses the id to distinguish between different error types and avoid error duplication. If an element with the same id is found in the list of currently aggregated errors, it will be replaced by the new one provided. Otherwise, a new error will be added to the list.
- Parameters
-
| id | The unique identification number of this error type for this ErrorPublisher. |
| description | A short and succinct description of the error. |
◆ addOneshotError()
| void mrs_lib::errorgraph::ErrorPublisher::addOneshotError |
( |
const std::string & |
description | ) |
|
Add an error that only appears once. This overload assumes that the error is unique, so it cannot be duplicate and doesn't need an identifier. Useful for errors during initialization that lead to termination of the node anyways.
- Parameters
-
| description | A short and succinct description of the error. |
◆ addWaitingForNodeError()
| void mrs_lib::errorgraph::ErrorPublisher::addWaitingForNodeError |
( |
const node_id_t & |
node_id | ) |
|
Add a special error type waiting_for_node. Use this whenever your node is blocked because it waits for some kind of input from another node, such as a transformation, messages, a service, etc. This helps construct the Errorgraph and decide which errors are the roots problems blocking the system. If you don't know the component of the node for the node_id, use main.
- Parameters
-
| node_id | Identifier of the node and component that is being waited for. If the component is unknown, use main. |
◆ addWaitingForTopicError()
| void mrs_lib::errorgraph::ErrorPublisher::addWaitingForTopicError |
( |
const std::string & |
topic_name | ) |
|
Add a special error type waiting_for_topic. You should prioritize using the addWaitingForNodeError() method if you know the node that should publish this topic to provide better information to the Errorgraph. Use this method if the node publishing the topic is unknown or can change.
- Parameters
-
| topic_name | Full name of the topic that is being waited for. |
◆ flushAndShutdown()
| void mrs_lib::errorgraph::ErrorPublisher::flushAndShutdown |
( |
| ) |
|
Publishes all aggregated errors and calls rclcpp::shutdown().
- Note
- To make sure that the published messages are propagated through ROS to any subscribers, the method waits 1s after publishing before calling rclcpp::shutdown().
The documentation for this class was generated from the following files: