Class DiagnosticBridgeNode
Defined in File diagnostic_bridge_node.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class DiagnosticBridgeNode : public rclcpp::Node
Bridge node that converts ROS2 /diagnostics messages to FaultManager faults.
Subscribes to /diagnostics topic and forwards diagnostic status messages to the FaultManager via the ReportFault service.
Severity mapping:
OK (0) -> PASSED event (healing)
WARN (1) -> WARN severity (1)
ERROR (2) -> ERROR severity (2)
STALE (3) -> CRITICAL severity (3)
Example launch configuration:
diagnostic_bridge: ros__parameters: diagnostics_topic: "/diagnostics" auto_generate_codes: true # Custom mappings: "name_to_code.<diagnostic_name>": "<FAULT_CODE>" "name_to_code.motor_controller: Status": "MOTOR_001"
Public Functions
-
explicit DiagnosticBridgeNode(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())
-
std::string map_to_fault_code(const std::string &diagnostic_name) const
Map diagnostic name to fault code Uses custom mapping if available, otherwise auto-generates from name
Public Static Functions
-
static std::optional<uint8_t> map_to_severity(uint8_t diagnostic_level)
Map DiagnosticStatus level to Fault severity Returns std::nullopt if level is OK (should send PASSED instead)
-
static bool is_ok_level(uint8_t diagnostic_level)
Check if diagnostic level indicates OK status.