galactic/include/diagnostic_updater/update_functions.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #ifndef DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
38 #define DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
39 
40 #include <math.h>
41 #include <memory>
42 #include <string>
43 #include <vector>
44 
45 #include "diagnostic_updater/diagnostic_updater.hpp"
46 
47 namespace diagnostic_updater
48 {
53 struct FrequencyStatusParam
54 {
60  double * min_freq, double * max_freq,
61  double tolerance = 0.1, int window_size = 5)
62  : min_freq_(min_freq), max_freq_(max_freq), tolerance_(tolerance),
63  window_size_(window_size) {}
64 
71  double * min_freq_;
72 
79  double * max_freq_;
80 
91  double tolerance_;
92 
96  int window_size_;
97 };
98 
110 class FrequencyStatus : public DiagnosticTask
111 {
112 private:
113  const FrequencyStatusParam params_;
114 
115  int count_;
116  std::vector<rclcpp::Time> times_;
117  std::vector<int> seq_nums_;
118  int hist_indx_;
119  std::mutex lock_;
120  rclcpp::Logger debug_logger_;
121 
122 public:
127  FrequencyStatus(const FrequencyStatusParam & params, std::string name)
128  : DiagnosticTask(name), params_(params), times_(params_.window_size_),
129  seq_nums_(params_.window_size_),
130  debug_logger_(rclcpp::get_logger("FrequencyStatus_debug_logger"))
131  {
132  clear();
133  }
134 
140  explicit FrequencyStatus(const FrequencyStatusParam & params)
141  : FrequencyStatus(params, "Frequency Status")
142  {}
143 
148  void clear()
149  {
150  std::unique_lock<std::mutex> lock(lock_);
151  rclcpp::Time curtime = rclcpp::Clock().now();
152  count_ = 0;
153 
154  for (int i = 0; i < params_.window_size_; i++) {
155  times_[i] = curtime;
156  seq_nums_[i] = count_;
157  }
158 
159  hist_indx_ = 0;
160  }
161 
165  void tick()
166  {
167  std::unique_lock<std::mutex> lock(lock_);
168  RCLCPP_DEBUG(debug_logger_, "TICK %i", count_);
169  count_++;
170  }
171 
173  {
174  std::unique_lock<std::mutex> lock(lock_);
175  rclcpp::Time curtime = rclcpp::Clock().now();
176 
177  int curseq = count_;
178  int events = curseq - seq_nums_[hist_indx_];
179  double window = (curtime - times_[hist_indx_]).seconds();
180  double freq = events / window;
181  seq_nums_[hist_indx_] = curseq;
182  times_[hist_indx_] = curtime;
184 
185  if (events == 0) {
186  stat.summary(2, "No events recorded.");
187  } else if (freq < *params_.min_freq_ * (1 - params_.tolerance_)) {
188  stat.summary(1, "Frequency too low.");
189  } else if (freq > *params_.max_freq_ * (1 + params_.tolerance_)) {
190  stat.summary(1, "Frequency too high.");
191  } else {
192  stat.summary(0, "Desired frequency met");
193  }
194 
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);
199  if (*params_.min_freq_ == *params_.max_freq_) {
200  stat.addf("Target frequency (Hz)", "%f", *params_.min_freq_);
201  }
202  if (*params_.min_freq_ > 0) {
203  stat.addf(
204  "Minimum acceptable frequency (Hz)", "%f",
206  }
207  if (std::isfinite(*params_.max_freq_)) {
208  stat.addf(
209  "Maximum acceptable frequency (Hz)", "%f",
211  }
212  }
213 };
214 
220 struct TimeStampStatusParam
221 {
227  const double min_acceptable = -1,
228  const double max_acceptable = 5)
229  : max_acceptable_(max_acceptable), min_acceptable_(min_acceptable) {}
230 
235  double max_acceptable_;
236 
241  double min_acceptable_;
242 };
243 
249 static TimeStampStatusParam DefaultTimeStampStatusParam =
250  TimeStampStatusParam();
251 
263 class TimeStampStatus : public DiagnosticTask
264 {
265 private:
266  void init()
267  {
268  early_count_ = 0;
269  late_count_ = 0;
270  zero_count_ = 0;
271  zero_seen_ = false;
272  max_delta_ = 0;
273  min_delta_ = 0;
274  deltas_valid_ = false;
275  }
276 
277 public:
283  const TimeStampStatusParam & params,
284  std::string name,
285  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
286  : DiagnosticTask(name), params_(params), clock_ptr_(clock)
287  {
288  init();
289  }
290 
296  explicit TimeStampStatus(
297  const TimeStampStatusParam & params,
298  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
299  : DiagnosticTask("Timestamp Status"), params_(params), clock_ptr_(clock)
300  {
301  init();
302  }
303 
309  explicit TimeStampStatus(
310  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
311  : DiagnosticTask("Timestamp Status"), clock_ptr_(clock) {init();}
312 
320  void tick(double stamp)
321  {
322  std::unique_lock<std::mutex> lock(lock_);
323 
324  if (stamp == 0) {
325  zero_seen_ = true;
326  } else {
327  const double delta = clock_ptr_->now().seconds() - stamp;
328 
329  if (!deltas_valid_ || delta > max_delta_) {
330  max_delta_ = delta;
331  }
332 
333  if (!deltas_valid_ || delta < min_delta_) {
334  min_delta_ = delta;
335  }
336 
337  deltas_valid_ = true;
338  }
339  }
340 
347  void tick(const rclcpp::Time t) {tick(t.seconds());}
348 
350  {
351  std::unique_lock<std::mutex> lock(lock_);
352 
353  stat.summary(0, "Timestamps are reasonable.");
354  if (!deltas_valid_) {
355  stat.summary(1, "No data since last update.");
356  } else {
358  stat.summary(2, "Timestamps too far in future seen.");
359  early_count_++;
360  }
361 
363  stat.summary(2, "Timestamps too far in past seen.");
364  late_count_++;
365  }
366 
367  if (zero_seen_) {
368  stat.summary(2, "Zero timestamp seen.");
369  zero_count_++;
370  }
371  }
372 
373  stat.addf("Earliest timestamp delay:", "%f", min_delta_);
374  stat.addf("Latest timestamp delay:", "%f", max_delta_);
375  stat.addf(
376  "Earliest acceptable timestamp delay:", "%f",
378  stat.addf(
379  "Latest acceptable timestamp delay:", "%f",
381  stat.add("Late diagnostic update count:", late_count_);
382  stat.add("Early diagnostic update count:", early_count_);
383  stat.add("Zero seen diagnostic update count:", zero_count_);
384 
385  deltas_valid_ = false;
386  min_delta_ = 0;
387  max_delta_ = 0;
388  zero_seen_ = false;
389  }
390 
391 private:
392  TimeStampStatusParam params_;
393  int early_count_;
394  int late_count_;
395  int zero_count_;
396  bool zero_seen_;
397  double max_delta_;
398  double min_delta_;
399  bool deltas_valid_;
400  const rclcpp::Clock::SharedPtr clock_ptr_;
401  std::mutex lock_;
402 };
403 
410 class Heartbeat : public DiagnosticTask
411 {
412 public:
417  Heartbeat()
418  : DiagnosticTask("Heartbeat") {}
419 
421  {
422  stat.summary(0, "Alive");
423  }
424 };
425 } // namespace diagnostic_updater
426 
427 #endif // DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
diagnostic_updater::FrequencyStatus::run
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
diagnostic_updater::DefaultTimeStampStatusParam
static TimeStampStatusParam DefaultTimeStampStatusParam
diagnostic_updater::TimeStampStatus::max_delta_
double max_delta_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:387
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
diagnostic_updater::TimeStampStatus::late_count_
int late_count_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:384
diagnostic_updater::DiagnosticTask::DiagnosticTask
DiagnosticTask(const std::string name)
diagnostic_updater::FrequencyStatus::count_
int count_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:115
diagnostic_updater::FrequencyStatus::params_
const FrequencyStatusParam params_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:113
diagnostic_updater::FrequencyStatusParam::max_freq_
double * max_freq_
Maximum acceptable frequency.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:79
diagnostic_updater::TimeStampStatusParam::min_acceptable_
double min_acceptable_
Minimum acceptable difference between two timestamps.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:239
diagnostic_updater::TimeStampStatus::zero_seen_
bool zero_seen_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:386
diagnostic_updater::FrequencyStatusParam::FrequencyStatusParam
FrequencyStatusParam(double *min_freq, double *max_freq, double tolerance=0.1, int window_size=5)
diagnostic_updater::TimeStampStatus::TimeStampStatus
TimeStampStatus()
diagnostic_updater::FrequencyStatus::times_
std::vector< ros::Time > times_
Definition: update_functions.h:110
diagnostic_updater::FrequencyStatus::tick
void tick()
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
diagnostic_updater::FrequencyStatus::hist_indx_
int hist_indx_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:118
diagnostic_updater::Heartbeat::Heartbeat
Heartbeat()
api.setup.name
name
Definition: python/api/setup.py:12
diagnostic_updater::TimeStampStatus::tick
void tick(const ros::Time t)
diagnostic_updater
Author: Blaise Gassend.
diagnostic_updater::TimeStampStatus::init
void init()
diagnostic_updater::TimeStampStatusParam::max_acceptable_
double max_acceptable_
Maximum acceptable difference between two timestamps.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:233
diagnostic_updater::TimeStampStatus::run
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
diagnostic_updater::TimeStampStatus::lock_
boost::mutex lock_
Definition: foxy/include/diagnostic_updater/update_functions.hpp:402
std_msgs::Time
::std_msgs::Time_< std::allocator< void > > Time
Definition: Time.h:48
diagnostic_updater::FrequencyStatus::FrequencyStatus
FrequencyStatus(const FrequencyStatusParam &params)
diagnostic_updater::FrequencyStatusParam::min_freq_
double * min_freq_
Minimum acceptable frequency.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:71
diagnostic_updater::FrequencyStatus::lock_
boost::mutex lock_
Definition: foxy/include/diagnostic_updater/update_functions.hpp:120
diagnostic_updater::TimeStampStatus::deltas_valid_
bool deltas_valid_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:389
diagnostic_updater::FrequencyStatus::seq_nums_
std::vector< int > seq_nums_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:117
diagnostic_updater::DiagnosticStatusWrapper::addf
void addf(const std::string &key, const char *format,...)
Definition: eloquent/include/diagnostic_updater/diagnostic_status_wrapper.hpp:282
ROS::seconds
double seconds(ROS::Duration duration)
Definition: ros_wrapper.cpp:180
diagnostic_updater::FrequencyStatusParam::tolerance_
double tolerance_
Tolerance with which bounds must be satisfied.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:91
diagnostic_updater::DiagnosticStatusWrapper
Wrapper for the diagnostic_msgs::msg::DiagnosticStatus message that makes it easier to update.
Definition: eloquent/include/diagnostic_updater/diagnostic_status_wrapper.hpp:68
diagnostic_updater::FrequencyStatus::clear
void clear()
diagnostic_updater::TimeStampStatus::early_count_
int early_count_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:383
diagnostic_updater::TimeStampStatus::params_
TimeStampStatusParam params_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:382
diagnostic_updater::TimeStampStatusParam::TimeStampStatusParam
TimeStampStatusParam(const double min_acceptable=-1, const double max_acceptable=5)
diagnostic_updater::FrequencyStatusParam::window_size_
int window_size_
Number of events to consider in the statistics.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:96
t
geometry_msgs::TransformStamped t
diagnostic_updater::TimeStampStatus::min_delta_
double min_delta_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:388
diagnostic_updater::TimeStampStatus::zero_count_
int zero_count_
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:385
diagnostic_updater::Heartbeat::run
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