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=true, const std::string & name="rate bound check") Constructs RateBoundstatus, which inherits diagnostic_updater::DiagnosticTask. |
|
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 |
---|---|
StateHolder | candidate_state_ |
std::shared_ptr< rclcpp::Clock > | clock_ |
StateHolder | current_state_ |
std::optional< double > | frequency_ |
bool | immediate_error_report_ |
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 |
---|---|
unsigned char | get_level (const StateHolder & state) |
std::string | get_level_string (unsigned char level) |
std::string | get_msg (const StateHolder & state) |
size_t | get_num_observations (const StateHolder & 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=true,
const std::string & name="rate bound check"
)
Parameters:
parent_node
The node from which clock type and parameters are read.ok_params
The pair of min/max frequency for the topic rate to be recognized as "OK".warn_params
The 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_transition
The number of the successive observations for the status transition. E.g., the status will not be changed from OK to WARN until successivenum_frame_transition
WARNs are observed.immediate_error_report
If true (default), errors related to the rate bounds will be reported immediately once observed; otherwise, the hysteresis damping method usingnum_frame_transition
will be adoptedname
The arbitrary string to be assigned for this diagnostic task. This name will not be exposed in the actual published topics.
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 candidate_state_
StateHolder custom_diagnostic_tasks::RateBoundStatus::candidate_state_;
variable clock_
std::shared_ptr<rclcpp::Clock> custom_diagnostic_tasks::RateBoundStatus::clock_;
variable current_state_
StateHolder custom_diagnostic_tasks::RateBoundStatus::current_state_;
variable frequency_
std::optional<double> custom_diagnostic_tasks::RateBoundStatus::frequency_;
variable immediate_error_report_
bool custom_diagnostic_tasks::RateBoundStatus::immediate_error_report_;
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 get_level
static inline unsigned char custom_diagnostic_tasks::RateBoundStatus::get_level (
const StateHolder & state
)
function get_level_string
static inline std::string custom_diagnostic_tasks::RateBoundStatus::get_level_string (
unsigned char level
)
function get_msg
static inline std::string custom_diagnostic_tasks::RateBoundStatus::get_msg (
const StateHolder & state
)
function get_num_observations
static inline size_t custom_diagnostic_tasks::RateBoundStatus::get_num_observations (
const StateHolder & state
)
The documentation for this class was generated from the following file nebula_ros/include/nebula_ros/common/diagnostics/rate_bound_status.hpp