update_functions.h
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_STATUS__UPDATE_FUNCTIONS_H__
39 #define __DIAGNOSTIC_STATUS__UPDATE_FUNCTIONS_H__
40 
41 #include <diagnostic_updater/diagnostic_updater.h>
42 #include <math.h>
43 
44 namespace diagnostic_updater
45 {
46 
51  struct FrequencyStatusParam
52  {
57  FrequencyStatusParam(double *min_freq, double *max_freq, double tolerance = 0.1, int window_size = 5) :
58  min_freq_(min_freq), max_freq_(max_freq), tolerance_(tolerance), window_size_(window_size)
59  {}
60 
67  double *min_freq_;
68 
75  double *max_freq_;
76 
87  double tolerance_;
88 
92  int window_size_;
93  };
94 
104  class FrequencyStatus : public DiagnosticTask
105  {
106  private:
107  const FrequencyStatusParam params_;
108 
109  int count_;
110  std::vector <ros::Time> times_;
111  std::vector <int> seq_nums_;
112  int hist_indx_;
113  std::mutex lock_;
114 
115  public:
120  FrequencyStatus(const FrequencyStatusParam &params) :
121  DiagnosticTask("Frequency Status"), params_(params),
123  {
124  clear();
125  }
126 
131  void clear()
132  {
133  std::lock_guard<std::mutex> lock(lock_);
134  ros::Time curtime = ros::Time::now();
135  count_ = 0;
136 
137  for (int i = 0; i < params_.window_size_; i++)
138  {
139  times_[i] = curtime;
140  seq_nums_[i] = count_;
141  }
142 
143  hist_indx_ = 0;
144  }
145 
149  void tick()
150  {
151  std::lock_guard<std::mutex> lock(lock_);
152  //ROS_DEBUG("TICK %i", count_);
153  count_++;
154  }
155 
157  {
158  std::lock_guard<std::mutex> lock(lock_);
159  ros::Time curtime = ros::Time::now();
160  int curseq = count_;
161  int events = curseq - seq_nums_[hist_indx_];
162  double window = (curtime - times_[hist_indx_]).toSec();
163  double freq = events / window;
164  seq_nums_[hist_indx_] = curseq;
165  times_[hist_indx_] = curtime;
167 
168  if (events == 0)
169  {
170  stat.summary(2, "No events recorded.");
171  }
172  else if (freq < *params_.min_freq_ * (1 - params_.tolerance_))
173  {
174  stat.summary(1, "Frequency too low.");
175  }
176  else if (freq > *params_.max_freq_ * (1 + params_.tolerance_))
177  {
178  stat.summary(1, "Frequency too high.");
179  }
180  else
181  {
182  stat.summary(0, "Desired frequency met");
183  }
184 
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);
190  stat.addf("Target frequency (Hz)", "%f",*params_.min_freq_);
191  if (*params_.min_freq_ > 0)
192  stat.addf("Minimum acceptable frequency (Hz)", "%f",
194 #ifndef _MSC_VER
195  if (finite(*params_.max_freq_))
196  stat.addf("Maximum acceptable frequency (Hz)", "%f",
198 #endif
199  }
200  };
201 
207  struct TimeStampStatusParam
208  {
213  TimeStampStatusParam(const double min_acceptable = -1, const double max_acceptable = 5) :
214  max_acceptable_(max_acceptable), min_acceptable_(min_acceptable)
215  {}
216 
221  double max_acceptable_;
222 
227  double min_acceptable_;
228 
229  };
230 
237 
249  class TimeStampStatus : public DiagnosticTask
250  {
251  private:
252  void init()
253  {
254  early_count_ = 0;
255  late_count_ = 0;
256  zero_count_ = 0;
257  zero_seen_ = false;
258  max_delta_ = 0;
259  min_delta_ = 0;
260  deltas_valid_ = false;
261  }
262 
263  public:
268  TimeStampStatus(const TimeStampStatusParam &params) :
269  DiagnosticTask("Timestamp Status"),
270  params_(params)
271  {
272  init();
273  }
274 
279  TimeStampStatus() :
280  DiagnosticTask("Timestamp Status")
281  {
282  init();
283  }
284 
292  void tick(double stamp)
293  {
294  std::lock_guard<std::mutex> lock(lock_);
295 
296  if (stamp == 0)
297  {
298  zero_seen_ = true;
299  }
300  else
301  {
302  double delta = ros::Time::now().toSec() - stamp;
303 
304  if (!deltas_valid_ || delta > max_delta_)
305  max_delta_ = delta;
306 
307  if (!deltas_valid_ || delta < min_delta_)
308  min_delta_ = delta;
309 
310  deltas_valid_ = true;
311  }
312  }
313 
321  void tick(const ros::Time t)
322  {
323  tick(t.toSec());
324  }
325 
327  {
328  std::lock_guard<std::mutex> lock(lock_);
329 
330  stat.summary(0, "Timestamps are reasonable.");
331  if (!deltas_valid_)
332  {
333  stat.summary(1, "No data since last update.");
334  }
335  else
336  {
338  {
339  stat.summary(2, "Timestamps too far in future seen.");
340  early_count_++;
341  }
342 
344  {
345  stat.summary(2, "Timestamps too far in past seen.");
346  late_count_++;
347  }
348 
349  if (zero_seen_)
350  {
351  stat.summary(2, "Zero timestamp seen.");
352  zero_count_++;
353  }
354  }
355 
356  stat.addf("Earliest timestamp delay:", "%f", min_delta_);
357  stat.addf("Latest timestamp delay:", "%f", max_delta_);
358  stat.addf("Earliest acceptable timestamp delay:", "%f", params_.min_acceptable_);
359  stat.addf("Latest acceptable timestamp delay:", "%f", params_.max_acceptable_);
360  stat.add("Late diagnostic update count:", late_count_);
361  stat.add("Early diagnostic update count:", early_count_);
362  stat.add("Zero seen diagnostic update count:", zero_count_);
363 
364  deltas_valid_ = false;
365  min_delta_ = 0;
366  max_delta_ = 0;
367  zero_seen_ = false;
368  }
369 
370  private:
371  TimeStampStatusParam params_;
372  int early_count_;
373  int late_count_;
374  int zero_count_;
375  bool zero_seen_;
376  double max_delta_;
377  double min_delta_;
378  bool deltas_valid_;
379  std::mutex lock_;
380  };
381 
382 };
383 
384 #endif
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)
TimeBase< Time, Duration >::toSec
double toSec() const
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::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
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
ros::Time
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
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
ros::Time::now
static Time now()


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:13