README
ros2_medkit_msgs
ROS 2 message and service definitions for the ros2_medkit fault management system.
Overview
This package provides the interface definitions used by the fault management components:
FaultManager (
ros2_medkit_fault_manager) - Central fault aggregation and lifecycle managementFaultReporter (
ros2_medkit_fault_reporter) - Client library for fault reportingGateway (
ros2_medkit_gateway) - REST API endpoints for fault access
Messages
Fault.msg
Core fault data model representing an aggregated fault condition with AUTOSAR DEM-style debounce filtering.
Field |
Type |
Description |
|---|---|---|
|
string |
Global fault identifier (e.g., “MOTOR_OVERHEAT”) |
|
uint8 |
Severity level (use SEVERITY_* constants) |
|
string |
Human-readable description |
|
builtin_interfaces/Time |
When fault was first reported |
|
builtin_interfaces/Time |
When fault was last reported (FAILED or PASSED) |
|
uint32 |
Total FAILED events aggregated across all sources |
|
string |
Current status (see STATUS_* constants) |
|
string[] |
List of source identifiers that reported this fault |
Severity Levels:
Constant |
Value |
Description |
|---|---|---|
|
0 |
Informational, no action required |
|
1 |
May require attention, no impact on functionality |
|
2 |
Impacts functionality, requires intervention |
|
3 |
Severe, may compromise safety or system operation. Bypasses debounce. |
Status Constants:
Constant |
Description |
|---|---|
|
Debounce counter < 0 but above confirmation threshold |
|
Debounce counter > 0 but below healing threshold |
|
Fault confirmed (counter <= threshold, e.g., -3) |
|
Fault healed by PASSED events (if healing enabled) |
|
Fault manually cleared via ClearFault service |
Status Lifecycle (Debounce Model):
PREFAILED ←→ PREPASSED → HEALED (retained)
↓
CONFIRMED → CLEARED (manual)
FAILED events decrement counter (towards confirmation)
PASSED events increment counter (towards healing)
CRITICAL severity bypasses debounce and confirms immediately
FaultEvent.msg
Real-time fault event notification for SSE streaming (published on /fault_manager/events).
Field |
Type |
Description |
|---|---|---|
|
string |
Event type (see constants below) |
|
Fault |
The fault data (state after event) |
|
builtin_interfaces/Time |
When the event occurred |
Event Types:
Constant |
Trigger |
|---|---|
|
Fault transitions PREFAILED → CONFIRMED |
|
Fault transitions to CLEARED |
|
Fault data changes without status transition |
Services
ReportFault.srv
Report a fault event (FAILED or PASSED) to the FaultManager.
Request:
Field |
Type |
Description |
|---|---|---|
|
string |
Global identifier (UPPER_SNAKE_CASE, max 64 chars) |
|
uint8 |
Event type: EVENT_FAILED (0) or EVENT_PASSED (1) |
|
uint8 |
Severity level (0-3, only for FAILED events) |
|
string |
Human-readable description (only for FAILED events) |
|
string |
Reporting node FQN (e.g., “/powertrain/engine/temp_sensor”) |
Response:
Field |
Type |
Description |
|---|---|---|
|
bool |
True if the event was accepted |
Event Types:
EVENT_FAILED(0): Fault condition detected - decrements debounce counterEVENT_PASSED(1): Fault condition cleared - increments debounce counter
ListFaults.srv
Query faults with optional filtering.
Request:
Field |
Type |
Description |
|---|---|---|
|
bool |
If true, filter by severity field; if false, return all severities |
|
uint8 |
Severity level (0-3), only used if filter_by_severity is true |
|
string[] |
Statuses to include (empty = CONFIRMED only) |
Response:
Field |
Type |
Description |
|---|---|---|
|
Fault[] |
Matching faults |
Examples:
Default (active faults):
filter_by_severity=false, statuses=[]→ all CONFIRMED faultsOnly errors:
filter_by_severity=true, severity=2, statuses=[]→ CONFIRMED with ERRORAll faults:
filter_by_severity=false, statuses=["PREFAILED", "CONFIRMED", "CLEARED"]Historical:
filter_by_severity=false, statuses=["CLEARED"]
ClearFault.srv
Clear/acknowledge a fault. Cleared faults are retained and queryable with statuses=["CLEARED"].
Request:
Field |
Type |
Description |
|---|---|---|
|
string |
The fault to clear |
Response:
Field |
Type |
Description |
|---|---|---|
|
bool |
True if fault was cleared |
|
string |
Status or error message |
Usage
C++
#include "ros2_medkit_msgs/msg/fault.hpp"
#include "ros2_medkit_msgs/srv/report_fault.hpp"
// Create a fault message
ros2_medkit_msgs::msg::Fault fault;
fault.fault_code = "MOTOR_OVERHEAT";
fault.severity = ros2_medkit_msgs::msg::Fault::SEVERITY_ERROR;
fault.status = ros2_medkit_msgs::msg::Fault::STATUS_CONFIRMED;
Python
from ros2_medkit_msgs.msg import Fault
from ros2_medkit_msgs.srv import ReportFault
# Create a fault message
fault = Fault()
fault.fault_code = "MOTOR_OVERHEAT"
fault.severity = Fault.SEVERITY_ERROR
fault.status = Fault.STATUS_CONFIRMED
Building
colcon build --packages-select ros2_medkit_msgs
source install/setup.bash # or setup.zsh for zsh users
Verifying
ros2 interface show ros2_medkit_msgs/msg/Fault
ros2 interface show ros2_medkit_msgs/srv/ReportFault
License
Apache-2.0