Abstract base class for checking Topic Publisher/Subscriber counts.
More...
#include <topic_pub_sub_check_base.hpp>
|
| void | set_config (const std::string topic_name, const uint32_t timeout_ms, const size_t expected_count=1, const ComparisonMode mode=ComparisonMode::EQUAL) |
| | Configure the check settings.
|
| |
| virtual void | prepare_check (rclcpp::Node::SharedPtr node) override=0 |
| | Prepares the check before execution.
|
| |
| virtual size_t | get_count (rclcpp::Node::SharedPtr node, const std::string &topic)=0 |
| |
| virtual std::string | get_target_type () const =0 |
| |
| 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.
|
| |
|
| 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.
|
| |
Abstract base class for checking Topic Publisher/Subscriber counts.
◆ get_count()
| virtual size_t system_health_check::base::TopicCountCheckBase::get_count |
( |
rclcpp::Node::SharedPtr |
node, |
|
|
const std::string & |
topic |
|
) |
| |
|
protectedpure virtual |
◆ get_target_type()
| virtual std::string system_health_check::base::TopicCountCheckBase::get_target_type |
( |
| ) |
const |
|
protectedpure virtual |
◆ prepare_check()
| virtual void system_health_check::base::TopicCountCheckBase::prepare_check |
( |
rclcpp::Node::SharedPtr |
node | ) |
|
|
overrideprotectedpure virtual |
Prepares the check before execution.
- Parameters
-
| node | Shared pointer to the ROS 2 node. |
Derived classes can override this function to perform any necessary setup.
Reimplemented from system_health_check::base::SystemCheckBase.
◆ set_config()
| void system_health_check::base::TopicCountCheckBase::set_config |
( |
const std::string |
topic_name, |
|
|
const uint32_t |
timeout_ms, |
|
|
const size_t |
expected_count = 1, |
|
|
const ComparisonMode |
mode = ComparisonMode::EQUAL |
|
) |
| |
|
inlineprotected |
Configure the check settings.
- Parameters
-
| topic_name | Topic name to check. |
| timeout_ms | Timeout in milliseconds. |
| expected_count | Expected count of publishers/subscribers. |
| mode | Comparison mode (GREATER_OR_EQUAL or EQUAL). Default is ComparisonMode::EQUAL. |
◆ expected_count_
| size_t system_health_check::base::TopicCountCheckBase::expected_count_ = 1 |
|
protected |
◆ mode_
◆ timeout_ms_
| uint32_t system_health_check::base::TopicCountCheckBase::timeout_ms_ = 1000 |
|
protected |
◆ topic_name_
| std::string system_health_check::base::TopicCountCheckBase::topic_name_ |
|
protected |
The documentation for this class was generated from the following file: