Go to the documentation of this file.
38 #ifndef DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
39 #define DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
45 #include "diagnostic_updater/diagnostic_updater.hpp"
53 struct FrequencyStatusParam
60 double * min_freq,
double * max_freq,
61 double tolerance = 0.1,
int window_size = 5)
110 class FrequencyStatus :
public DiagnosticTask
113 const FrequencyStatusParam
params_;
116 std::vector<rclcpp::Time>
times_;
120 rclcpp::Logger debug_logger_;
130 debug_logger_(rclcpp::get_logger(
"FrequencyStatus_debug_logger"))
150 std::unique_lock<std::mutex> lock(
lock_);
167 std::unique_lock<std::mutex> lock(
lock_);
168 RCLCPP_DEBUG(debug_logger_,
"TICK %i",
count_);
174 std::unique_lock<std::mutex> lock(
lock_);
180 double freq = events / window;
186 stat.
summary(2,
"No events recorded.");
188 stat.
summary(1,
"Frequency too low.");
190 stat.
summary(1,
"Frequency too high.");
192 stat.
summary(0,
"Desired frequency met");
195 stat.
addf(
"Events in window",
"%d", events);
196 stat.
addf(
"Events since startup",
"%d",
count_);
197 stat.
addf(
"Duration of window (s)",
"%f", window);
198 stat.
addf(
"Actual frequency (Hz)",
"%f", freq);
203 stat.
addf(
"Minimum acceptable frequency (Hz)",
"%f",
207 stat.
addf(
"Maximum acceptable frequency (Hz)",
"%f",
218 struct TimeStampStatusParam
225 const double min_acceptable = -1,
226 const double max_acceptable = 5)
312 void tick(
double stamp)
314 std::unique_lock<std::mutex> lock(
lock_);
319 double delta = rclcpp::Clock().now().seconds() - stamp;
343 std::unique_lock<std::mutex> lock(
lock_);
345 stat.
summary(0,
"Timestamps are reasonable.");
347 stat.
summary(1,
"No data since last update.");
350 stat.
summary(2,
"Timestamps too far in future seen.");
355 stat.
summary(2,
"Timestamps too far in past seen.");
360 stat.
summary(2,
"Zero timestamp seen.");
367 stat.
addf(
"Earliest acceptable timestamp delay:",
"%f",
369 stat.
addf(
"Latest acceptable timestamp delay:",
"%f",
399 class Heartbeat :
public DiagnosticTask
416 #endif // DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
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)
::std_msgs::Time_< std::allocator< void > > Time
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 seconds(ROS::Duration duration)
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
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:13