foxy/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 <memory>
43 #include <string>
44 #include <vector>
45 
46 #include "diagnostic_updater/diagnostic_updater.hpp"
47 
48 namespace diagnostic_updater
49 {
54 struct FrequencyStatusParam
55 {
61  double * min_freq, double * max_freq,
62  double tolerance = 0.1, int window_size = 5)
63  : min_freq_(min_freq), max_freq_(max_freq), tolerance_(tolerance),
64  window_size_(window_size) {}
65 
72  double * min_freq_;
73 
80  double * max_freq_;
81 
92  double tolerance_;
93 
97  int window_size_;
98 };
99 
111 class FrequencyStatus : public DiagnosticTask
112 {
113 private:
114  const FrequencyStatusParam params_;
115 
116  int count_;
117  std::vector<rclcpp::Time> times_;
118  std::vector<int> seq_nums_;
119  int hist_indx_;
120  std::mutex lock_;
121  rclcpp::Logger debug_logger_;
122 
123 public:
128  FrequencyStatus(const FrequencyStatusParam & params, std::string name)
131  debug_logger_(rclcpp::get_logger("FrequencyStatus_debug_logger"))
132  {
133  clear();
134  }
135 
141  explicit FrequencyStatus(const FrequencyStatusParam & params)
142  : FrequencyStatus(params, "Frequency Status")
143  {}
144 
149  void clear()
150  {
151  std::unique_lock<std::mutex> lock(lock_);
152  rclcpp::Time curtime = rclcpp::Clock().now();
153  count_ = 0;
154 
155  for (int i = 0; i < params_.window_size_; i++) {
156  times_[i] = curtime;
157  seq_nums_[i] = count_;
158  }
159 
160  hist_indx_ = 0;
161  }
162 
166  void tick()
167  {
168  std::unique_lock<std::mutex> lock(lock_);
169  RCLCPP_DEBUG(debug_logger_, "TICK %i", count_);
170  count_++;
171  }
172 
174  {
175  std::unique_lock<std::mutex> lock(lock_);
176  rclcpp::Time curtime = rclcpp::Clock().now();
177 
178  int curseq = count_;
179  int events = curseq - seq_nums_[hist_indx_];
180  double window = (curtime - times_[hist_indx_]).seconds();
181  double freq = events / window;
182  seq_nums_[hist_indx_] = curseq;
183  times_[hist_indx_] = curtime;
185 
186  if (events == 0) {
187  stat.summary(2, "No events recorded.");
188  } else if (freq < *params_.min_freq_ * (1 - params_.tolerance_)) {
189  stat.summary(1, "Frequency too low.");
190  } else if (freq > *params_.max_freq_ * (1 + params_.tolerance_)) {
191  stat.summary(1, "Frequency too high.");
192  } else {
193  stat.summary(0, "Desired frequency met");
194  }
195 
196  stat.addf("Events in window", "%d", events);
197  stat.addf("Events since startup", "%d", count_);
198  stat.addf("Duration of window (s)", "%f", window);
199  stat.addf("Actual frequency (Hz)", "%f", freq);
200  if (*params_.min_freq_ == *params_.max_freq_) {
201  stat.addf("Target frequency (Hz)", "%f", *params_.min_freq_);
202  }
203  if (*params_.min_freq_ > 0) {
204  stat.addf(
205  "Minimum acceptable frequency (Hz)", "%f",
207  }
208  if (std::isfinite(*params_.max_freq_)) {
209  stat.addf(
210  "Maximum acceptable frequency (Hz)", "%f",
212  }
213  }
214 };
215 
221 struct TimeStampStatusParam
222 {
228  const double min_acceptable = -1,
229  const double max_acceptable = 5)
230  : max_acceptable_(max_acceptable), min_acceptable_(min_acceptable) {}
231 
236  double max_acceptable_;
237 
242  double min_acceptable_;
243 };
244 
252 
264 class TimeStampStatus : public DiagnosticTask
265 {
266 private:
267  void init()
268  {
269  early_count_ = 0;
270  late_count_ = 0;
271  zero_count_ = 0;
272  zero_seen_ = false;
273  max_delta_ = 0;
274  min_delta_ = 0;
275  deltas_valid_ = false;
276  }
277 
278 public:
284  const TimeStampStatusParam & params,
285  std::string name,
286  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
287  : DiagnosticTask(name), params_(params), clock_ptr_(clock)
288  {
289  init();
290  }
291 
297  explicit TimeStampStatus(
298  const TimeStampStatusParam & params,
299  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
300  : DiagnosticTask("Timestamp Status"), params_(params), clock_ptr_(clock)
301  {
302  init();
303  }
304 
310  explicit TimeStampStatus(
311  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
312  : DiagnosticTask("Timestamp Status"), clock_ptr_(clock) {init();}
313 
321  void tick(double stamp)
322  {
323  std::unique_lock<std::mutex> lock(lock_);
324 
325  if (stamp == 0) {
326  zero_seen_ = true;
327  } else {
328  const double delta = clock_ptr_->now().seconds() - stamp;
329 
330  if (!deltas_valid_ || delta > max_delta_) {
331  max_delta_ = delta;
332  }
333 
334  if (!deltas_valid_ || delta < min_delta_) {
335  min_delta_ = delta;
336  }
337 
338  deltas_valid_ = true;
339  }
340  }
341 
348  void tick(const rclcpp::Time t) {tick(t.seconds());}
349 
351  {
352  std::unique_lock<std::mutex> lock(lock_);
353 
354  stat.summary(0, "Timestamps are reasonable.");
355  if (!deltas_valid_) {
356  stat.summary(1, "No data since last update.");
357  } else {
359  stat.summary(2, "Timestamps too far in future seen.");
360  early_count_++;
361  }
362 
364  stat.summary(2, "Timestamps too far in past seen.");
365  late_count_++;
366  }
367 
368  if (zero_seen_) {
369  stat.summary(2, "Zero timestamp seen.");
370  zero_count_++;
371  }
372  }
373 
374  stat.addf("Earliest timestamp delay:", "%f", min_delta_);
375  stat.addf("Latest timestamp delay:", "%f", max_delta_);
376  stat.addf(
377  "Earliest acceptable timestamp delay:", "%f",
379  stat.addf(
380  "Latest acceptable timestamp delay:", "%f",
382  stat.add("Late diagnostic update count:", late_count_);
383  stat.add("Early diagnostic update count:", early_count_);
384  stat.add("Zero seen diagnostic update count:", zero_count_);
385 
386  deltas_valid_ = false;
387  min_delta_ = 0;
388  max_delta_ = 0;
389  zero_seen_ = false;
390  }
391 
392 private:
393  TimeStampStatusParam params_;
394  int early_count_;
395  int late_count_;
396  int zero_count_;
397  bool zero_seen_;
398  double max_delta_;
399  double min_delta_;
400  bool deltas_valid_;
401  const rclcpp::Clock::SharedPtr clock_ptr_;
402  std::mutex lock_;
403 };
404 
411 class Heartbeat : public DiagnosticTask
412 {
413 public:
418  Heartbeat()
419  : DiagnosticTask("Heartbeat") {}
420 
422  {
423  stat.summary(0, "Alive");
424  }
425 };
426 } // namespace diagnostic_updater
427 
428 #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