Class custom_diagnostic_tasks::RateBoundStatus
ClassList > custom_diagnostic_tasks > RateBoundStatus
Diagnostic task to monitor the interval between events. More...
#include <rate_bound_status.hpp>
Inherits the following classes: diagnostic_updater::DiagnosticTask
Public Functions
| Type | Name |
|---|---|
| RateBoundStatus (const rclcpp::Node * parent_node, const RateBoundStatusParam & ok_params, const RateBoundStatusParam & warn_params, const size_t num_frame_transition=1, const bool immediate_error_report=false, const bool immediate_relax_state=true, const std::string & name="rate bound check") Constructs RateBoundStatus , which inherits diagnostic_updater::DiagnosticTask. |
|
| bool | is_ok (double observation) |
| bool | is_warn (double observation) |
| void | run (diagnostic_updater::DiagnosticStatusWrapper & stat) override function called every update |
| void | tick () Calculate the frequency of how much this function is called. |
Protected Attributes
| Type | Name |
|---|---|
| std::shared_ptr< rclcpp::Clock > | clock_ |
| std::optional< double > | frequency_ |
| HysteresisStateMachine | hysteresis_state_machine_ |
| std::mutex | lock_ |
| size_t | num_frame_transition_ |
| RateBoundStatusParam | ok_params_ |
| std::optional< double > | previous_frame_timestamp_ |
| RateBoundStatusParam | warn_params_ |
| bool | zero_seen_ |
Protected Functions
| Type | Name |
|---|---|
| double | get_now () |
Protected Static Functions
| Type | Name |
|---|---|
| std::string | generate_msg (const DiagnosticStatus_t & state) |
Detailed Description
This diagnostic task monitors the difference between consecutive events, and creates corresponding diagnostics. This task categorize observed intervals into OK/WARN/ERROR according to the value ranges passed via constructor arguments
Public Functions Documentation
function RateBoundStatus
Constructs RateBoundStatus , which inherits diagnostic_updater::DiagnosticTask.
inline custom_diagnostic_tasks::RateBoundStatus::RateBoundStatus (
const rclcpp::Node * parent_node,
const RateBoundStatusParam & ok_params,
const RateBoundStatusParam & warn_params,
const size_t num_frame_transition=1,
const bool immediate_error_report=false,
const bool immediate_relax_state=true,
const std::string & name="rate bound check"
)
Parameters:
parent_nodeThe node from which parameters are read.ok_paramsThe pair of min/max frequency for the topic rate to be recognized as "OK".warn_paramsThe pair of min/max frequency for the topic rate to be recognized as "WARN". These values should have a wider range thanok_params.num_frame_transitionThe number of the successive observations for the status transition. E.g., the status will not be changed from OK to WARN until successivenum_frame_transitionWARNs are observed.immediate_error_reportIf true, errors related to the rate bounds will be reported immediately once observed; otherwise, the hysteresis damping method usingnum_frame_transitionwill be adoptednameThe arbitrary string to be assigned for this diagnostic task. This name will not be exposed in the actual published topics.
function is_ok
inline bool custom_diagnostic_tasks::RateBoundStatus::is_ok (
double observation
)
function is_warn
inline bool custom_diagnostic_tasks::RateBoundStatus::is_warn (
double observation
)
function run
function called every update
inline void custom_diagnostic_tasks::RateBoundStatus::run (
diagnostic_updater::DiagnosticStatusWrapper & stat
) override
function tick
Calculate the frequency of how much this function is called.
inline void custom_diagnostic_tasks::RateBoundStatus::tick ()
Protected Attributes Documentation
variable clock_
std::shared_ptr<rclcpp::Clock> custom_diagnostic_tasks::RateBoundStatus::clock_;
variable frequency_
std::optional<double> custom_diagnostic_tasks::RateBoundStatus::frequency_;
variable hysteresis_state_machine_
HysteresisStateMachine custom_diagnostic_tasks::RateBoundStatus::hysteresis_state_machine_;
variable lock_
std::mutex custom_diagnostic_tasks::RateBoundStatus::lock_;
variable num_frame_transition_
size_t custom_diagnostic_tasks::RateBoundStatus::num_frame_transition_;
variable ok_params_
RateBoundStatusParam custom_diagnostic_tasks::RateBoundStatus::ok_params_;
variable previous_frame_timestamp_
std::optional<double> custom_diagnostic_tasks::RateBoundStatus::previous_frame_timestamp_;
variable warn_params_
RateBoundStatusParam custom_diagnostic_tasks::RateBoundStatus::warn_params_;
variable zero_seen_
bool custom_diagnostic_tasks::RateBoundStatus::zero_seen_;
Protected Functions Documentation
function get_now
inline double custom_diagnostic_tasks::RateBoundStatus::get_now ()
Protected Static Functions Documentation
function generate_msg
static inline std::string custom_diagnostic_tasks::RateBoundStatus::generate_msg (
const DiagnosticStatus_t & state
)
The documentation for this class was generated from the following file nebula_ros/include/nebula_ros/common/diagnostics/rate_bound_status.hpp