eloquent/include/diagnostic_updater/update_functions.hpp
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2009, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
37 
38 #ifndef DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
39 #define DIAGNOSTIC_UPDATER__UPDATE_FUNCTIONS_HPP_
40 
41 #include <math.h>
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)
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("Minimum acceptable frequency (Hz)", "%f",
205  }
206  if (std::isfinite(*params_.max_freq_)) {
207  stat.addf("Maximum acceptable frequency (Hz)", "%f",
209  }
210  }
211 };
212 
218 struct TimeStampStatusParam
219 {
225  const double min_acceptable = -1,
226  const double max_acceptable = 5)
227  : max_acceptable_(max_acceptable), min_acceptable_(min_acceptable) {}
228 
233  double max_acceptable_;
234 
239  double min_acceptable_;
240 };
241 
249 
261 class TimeStampStatus : public DiagnosticTask
262 {
263 private:
264  void init()
265  {
266  early_count_ = 0;
267  late_count_ = 0;
268  zero_count_ = 0;
269  zero_seen_ = false;
270  max_delta_ = 0;
271  min_delta_ = 0;
272  deltas_valid_ = false;
273  }
274 
275 public:
280  TimeStampStatus(const TimeStampStatusParam & params, std::string name)
281  : DiagnosticTask(name), params_(params)
282  {
283  init();
284  }
285 
291  explicit TimeStampStatus(const TimeStampStatusParam & params)
292  : DiagnosticTask("Timestamp Status"), params_(params)
293  {
294  init();
295  }
296 
303  : DiagnosticTask("Timestamp Status") {init();}
304 
312  void tick(double stamp)
313  {
314  std::unique_lock<std::mutex> lock(lock_);
315 
316  if (stamp == 0) {
317  zero_seen_ = true;
318  } else {
319  double delta = rclcpp::Clock().now().seconds() - stamp;
320 
321  if (!deltas_valid_ || delta > max_delta_) {
322  max_delta_ = delta;
323  }
324 
325  if (!deltas_valid_ || delta < min_delta_) {
326  min_delta_ = delta;
327  }
328 
329  deltas_valid_ = true;
330  }
331  }
332 
339  void tick(const rclcpp::Time t) {tick(t.seconds());}
340 
342  {
343  std::unique_lock<std::mutex> lock(lock_);
344 
345  stat.summary(0, "Timestamps are reasonable.");
346  if (!deltas_valid_) {
347  stat.summary(1, "No data since last update.");
348  } else {
350  stat.summary(2, "Timestamps too far in future seen.");
351  early_count_++;
352  }
353 
355  stat.summary(2, "Timestamps too far in past seen.");
356  late_count_++;
357  }
358 
359  if (zero_seen_) {
360  stat.summary(2, "Zero timestamp seen.");
361  zero_count_++;
362  }
363  }
364 
365  stat.addf("Earliest timestamp delay:", "%f", min_delta_);
366  stat.addf("Latest timestamp delay:", "%f", max_delta_);
367  stat.addf("Earliest acceptable timestamp delay:", "%f",
369  stat.addf("Latest acceptable timestamp delay:", "%f",
371  stat.add("Late diagnostic update count:", late_count_);
372  stat.add("Early diagnostic update count:", early_count_);
373  stat.add("Zero seen diagnostic update count:", zero_count_);
374 
375  deltas_valid_ = false;
376  min_delta_ = 0;
377  max_delta_ = 0;
378  zero_seen_ = false;
379  }
380 
381 private:
382  TimeStampStatusParam params_;
383  int early_count_;
384  int late_count_;
385  int zero_count_;
386  bool zero_seen_;
387  double max_delta_;
388  double min_delta_;
389  bool deltas_valid_;
390  std::mutex lock_;
391 };
392 
399 class Heartbeat : public DiagnosticTask
400 {
401 public:
406  Heartbeat()
407  : DiagnosticTask("Heartbeat") {}
408 
410  {
411  stat.summary(0, "Alive");
412  }
413 };
414 } // namespace diagnostic_updater
415 
416 #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::TimeStampStatusParam
A structure that holds the constructor parameters for the TimeStampStatus class.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:218
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::TimeStampStatus
Diagnostic task to monitor the interval between events.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:261
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::DiagnosticTask
DiagnosticTask is an abstract base class for collecting diagnostic data.
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:73
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
sick_scan_base.h
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