Class FaultManager
Defined in File fault_manager.hpp
Class Documentation
-
class FaultManager
Manager for fault management operations Provides interface to the ros2_medkit_fault_manager services
Public Functions
-
explicit FaultManager(rclcpp::Node *node)
-
FaultResult report_fault(const std::string &fault_code, uint8_t severity, const std::string &description, const std::string &source_id)
Report a fault from a component
- Parameters:
fault_code – Unique fault identifier
severity – Fault severity (0=INFO, 1=WARN, 2=ERROR, 3=CRITICAL)
description – Human-readable description
source_id – Component identifier (namespace path)
- Returns:
FaultResult with success status
-
FaultResult list_faults(const std::string &source_id = "", bool include_prefailed = true, bool include_confirmed = true, bool include_cleared = false, bool include_healed = false, bool include_muted = false, bool include_clusters = false)
Get all faults, optionally filtered by component
- Parameters:
source_id – Optional component identifier to filter by (empty = all)
include_prefailed – Include PREFAILED status faults (debounce not yet confirmed)
include_confirmed – Include CONFIRMED status faults
include_cleared – Include CLEARED status faults
include_healed – Include HEALED and PREPASSED status faults
include_muted – Include muted faults (correlation symptoms) in response
include_clusters – Include cluster info in response
- Returns:
FaultResult with array of faults (and optionally muted_faults and clusters)
-
FaultWithEnvResult get_fault_with_env(const std::string &fault_code, const std::string &source_id = "")
Get a specific fault by code with environment data
- Parameters:
fault_code – Fault identifier
source_id – Optional component identifier to verify fault belongs to component
- Returns:
FaultWithEnvResult with fault and environment_data, or error if not found
-
FaultResult get_fault(const std::string &fault_code, const std::string &source_id = "")
Get a specific fault by code (JSON result - legacy)
Note
Thread-safe: delegates to get_fault_with_env() which acquires get_mutex_. Do NOT call this method while holding get_mutex_.
- Parameters:
fault_code – Fault identifier
source_id – Optional component identifier to verify fault belongs to component
- Returns:
FaultResult with fault data or error if not found
-
FaultResult clear_fault(const std::string &fault_code)
Clear a fault
- Parameters:
fault_code – Fault identifier to clear
- Returns:
FaultResult with success status
-
FaultResult get_snapshots(const std::string &fault_code, const std::string &topic = "")
Get snapshots for a fault
- Parameters:
fault_code – Fault identifier
topic – Optional topic filter (empty = all topics)
- Returns:
FaultResult with snapshot data (JSON in data field)
-
FaultResult get_rosbag(const std::string &fault_code)
Get rosbag file info for a fault
- Parameters:
fault_code – Fault identifier
- Returns:
FaultResult with rosbag file path and metadata
-
FaultResult list_rosbags(const std::string &entity_fqn)
Get all rosbag files for an entity (batch operation)
- Parameters:
entity_fqn – Entity fully qualified name for prefix matching
- Returns:
FaultResult with arrays of rosbag metadata
-
bool is_available() const
Check if fault manager service is available
- Returns:
true if services are available
-
explicit FaultManager(rclcpp::Node *node)