10#ifndef _SYSTEM_CHECK_BASE_HPP
11#define _SYSTEM_CHECK_BASE_HPP
13#include <rclcpp/rclcpp.hpp>
36 bool check(rclcpp::Node::SharedPtr node)
50 std::lock_guard<std::mutex> lock(cache_mutex_);
51 if (results_cache_.count(
id)) {
52 cache_msg_ =
" (Cached) " + reports_cache_[id];
53 return results_cache_[id];
62 std::lock_guard<std::mutex> lock(cache_mutex_);
63 results_cache_[id] = result;
64 reports_cache_[id] =
report(node);
90 virtual void prepare_check([[maybe_unused]] rclcpp::Node::SharedPtr node) {};
98 virtual bool check_impl(rclcpp::Node::SharedPtr node) = 0;
106 virtual std::string
report_impl(rclcpp::Node::SharedPtr node) = 0;
109 std::string cache_msg_ =
"";
112 inline static std::unordered_map<std::string, bool> results_cache_;
113 inline static std::unordered_map<std::string, std::string> reports_cache_;
114 inline static std::mutex cache_mutex_;
Abstract base class for all system check plugins.
Definition: system_check_base.hpp:24
std::string report(rclcpp::Node::SharedPtr node)
Generates a human-readable report of the check.
Definition: system_check_base.hpp:75
virtual std::string report_impl(rclcpp::Node::SharedPtr node)=0
Generates a detailed report of the check.
virtual bool check_impl(rclcpp::Node::SharedPtr node)=0
Actual implementation of the check logic.
virtual void prepare_check(rclcpp::Node::SharedPtr node)
Prepares the check before execution.
Definition: system_check_base.hpp:90
virtual std::string get_unique_id() const
Generates a unique identifier for the check instance.
Definition: system_check_base.hpp:83
virtual ~SystemCheckBase()
Definition: system_check_base.hpp:26
bool check(rclcpp::Node::SharedPtr node)
Executes the system check with caching support.
Definition: system_check_base.hpp:36
Definition: action_server_check_base.hpp:25