Common
common packages for kyubic
 
Loading...
Searching...
No Matches
system_health_check::base::SystemCheckBase Class Referenceabstract

Abstract base class for all system check plugins. More...

#include <system_check_base.hpp>

+ Inheritance diagram for system_health_check::base::SystemCheckBase:

Public Member Functions

virtual ~SystemCheckBase ()
 
bool check (rclcpp::Node::SharedPtr node)
 Executes the system check with caching support.
 
std::string report (rclcpp::Node::SharedPtr node)
 Generates a human-readable report of the check.
 

Protected Member Functions

virtual std::string get_unique_id () const
 Generates a unique identifier for the check instance.
 
virtual void prepare_check (rclcpp::Node::SharedPtr node)
 Prepares the check before execution.
 
virtual bool check_impl (rclcpp::Node::SharedPtr node)=0
 Actual implementation of the check logic.
 
virtual std::string report_impl (rclcpp::Node::SharedPtr node)=0
 Generates a detailed report of the check.
 

Detailed Description

Abstract base class for all system check plugins.

Any package that wants to perform a system check must inherit from this class and implement the check() and report() methods.

Constructor & Destructor Documentation

◆ ~SystemCheckBase()

virtual system_health_check::base::SystemCheckBase::~SystemCheckBase ( )
inlinevirtual

Member Function Documentation

◆ check()

bool system_health_check::base::SystemCheckBase::check ( rclcpp::Node::SharedPtr  node)
inline

Executes the system check with caching support.

Parameters
nodeShared pointer to the ROS 2 node.
Returns
true if the check passes, false otherwise.

This function follows the NVI pattern. It first checks if a valid result exists in the cache for the generated ID. If found, it returns the cached result immediately. Otherwise, it invokes check_impl() and saves the result.

◆ check_impl()

virtual bool system_health_check::base::SystemCheckBase::check_impl ( rclcpp::Node::SharedPtr  node)
protectedpure virtual

Actual implementation of the check logic.

Note
Derived classes must implement this function instead of check.
Parameters
nodeShared pointer to the ROS 2 node.
Returns
true if the check passes, false otherwise.

Implemented in system_health_check::checks::PassCheck, and system_health_check::checks::FailCheck.

◆ get_unique_id()

virtual std::string system_health_check::base::SystemCheckBase::get_unique_id ( ) const
inlineprotectedvirtual

Generates a unique identifier for the check instance.

Used as a key for the result cache.

Returns
A unique string ID (e.g., "ClassName::TargetName::Params").

◆ prepare_check()

◆ report()

std::string system_health_check::base::SystemCheckBase::report ( rclcpp::Node::SharedPtr  node)
inline

Generates a human-readable report of the check.

Parameters
nodeShared pointer to the ROS 2 node.
Returns
A string containing diagnostic information.

◆ report_impl()

virtual std::string system_health_check::base::SystemCheckBase::report_impl ( rclcpp::Node::SharedPtr  node)
protectedpure virtual

Generates a detailed report of the check.

Parameters
nodeShared pointer to the ROS 2 node.
Returns
std::string A human-readable report string.

It should return a string containing diagnostic information (e.g., sensor values, error codes).

Implemented in system_health_check::checks::PassCheck, and system_health_check::checks::FailCheck.


The documentation for this class was generated from the following file: