Go to the documentation of this file.
38 #ifndef __DIAGNOSTIC_STATUS__UPDATE_FUNCTIONS_H__
39 #define __DIAGNOSTIC_STATUS__UPDATE_FUNCTIONS_H__
41 #include <diagnostic_updater/diagnostic_updater.h>
51 struct FrequencyStatusParam
57 FrequencyStatusParam(
double *min_freq,
double *max_freq,
double tolerance = 0.1,
int window_size = 5) :
104 class FrequencyStatus :
public DiagnosticTask
107 const FrequencyStatusParam
params_;
110 std::vector <ros::Time>
times_;
133 std::lock_guard<std::mutex> lock(
lock_);
151 std::lock_guard<std::mutex> lock(
lock_);
158 std::lock_guard<std::mutex> lock(
lock_);
163 double freq = events / window;
170 stat.
summary(2,
"No events recorded.");
174 stat.
summary(1,
"Frequency too low.");
178 stat.
summary(1,
"Frequency too high.");
182 stat.
summary(0,
"Desired frequency met");
185 stat.
addf(
"Events in window",
"%d", events);
186 stat.
addf(
"Events since startup",
"%d",
count_);
187 stat.
addf(
"Duration of window (s)",
"%f", window);
188 stat.
addf(
"Actual frequency (Hz)",
"%f",freq);
192 stat.
addf(
"Minimum acceptable frequency (Hz)",
"%f",
196 stat.
addf(
"Maximum acceptable frequency (Hz)",
"%f",
207 struct TimeStampStatusParam
292 void tick(
double stamp)
294 std::lock_guard<std::mutex> lock(
lock_);
328 std::lock_guard<std::mutex> lock(
lock_);
330 stat.
summary(0,
"Timestamps are reasonable.");
333 stat.
summary(1,
"No data since last update.");
339 stat.
summary(2,
"Timestamps too far in future seen.");
345 stat.
summary(2,
"Timestamps too far in past seen.");
351 stat.
summary(2,
"Zero timestamp seen.");
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
static TimeStampStatusParam DefaultTimeStampStatusParam
A structure that holds the constructor parameters for the TimeStampStatus class.
void add(const std::string &key, const bool &b)
Diagnostic task to monitor the interval between events.
DiagnosticTask(const std::string name)
const FrequencyStatusParam params_
double * max_freq_
Maximum acceptable frequency.
double min_acceptable_
Minimum acceptable difference between two timestamps.
FrequencyStatusParam(double *min_freq, double *max_freq, double tolerance=0.1, int window_size=5)
std::vector< ros::Time > times_
DiagnosticTask is an abstract base class for collecting diagnostic data.
void summary(const diagnostic_msgs::DiagnosticStatus &src)
void tick(const ros::Time t)
double max_acceptable_
Maximum acceptable difference between two timestamps.
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
FrequencyStatus(const FrequencyStatusParam ¶ms)
double * min_freq_
Minimum acceptable frequency.
std::vector< int > seq_nums_
void addf(const std::string &key, const char *format,...)
double tolerance_
Tolerance with which bounds must be satisfied.
Wrapper for the diagnostic_msgs::msg::DiagnosticStatus message that makes it easier to update.
TimeStampStatusParam params_
TimeStampStatusParam(const double min_acceptable=-1, const double max_acceptable=5)
int window_size_
Number of events to consider in the statistics.
geometry_msgs::TransformStamped t
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:13