timer.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2015, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 #ifndef SWRI_ROSCPP_TIMER_H_
30 #define SWRI_ROSCPP_TIMER_H_
31 
32 #include <ros/node_handle.h>
34 #include <swri_roscpp/timer_impl.h>
35 
36 namespace swri
37 {
38 class Timer
39 {
40  private:
42 
43  public:
44  Timer();
45 
46  template<class T>
48  ros::Duration period,
49  void(T::*callback)(const ros::TimerEvent&),
50  T *obj);
51 
52  Timer& operator=(const Timer &other);
53 
55  double desiredFrequency() const;
56 
57  void resetStatistics();
58 
59  // The number of times the timer callback has been called.
60  size_t ticks() const;
61 
62  // Frequency/Period of the timer callbacks.
63  double meanFrequencyHz() const;
64  ros::Duration meanPeriod() const;
65  ros::Duration minPeriod() const;
66  ros::Duration maxPeriod() const;
67  double meanPeriodMilliseconds() const;
68  double minPeriodMilliseconds() const;
69  double maxPeriodMilliseconds() const;
70 
71  // Average duration of the timer callback. These are tracked as
72  // wall durations because they are typically used as a rough profile
73  // of how long the callback takes to execute which is independent of
74  // simulated time.
78  double meanDurationMicroseconds() const;
79  double minDurationMicroseconds() const;
80  double maxDurationMicroseconds() const;
81 
83  DIAG_COUNT = 1 << 0,
84  DIAG_RATE = 1 << 1,
85  DIAG_DURATION = 1 << 2,
86 
87  DIAG_ALL = ~0,
89  };
90 
92  const std::string &name,
93  const int flags);
94 }; // class Timer
95 
96 
97 inline
99 {
100  // Setup an empty implementation so that we can assume impl_ is
101  // non-null and avoid a lot of unnecessary NULL checks.
103 }
104 
105 template<class T>
106 inline
108  ros::Duration period,
109  void(T::*callback)(const ros::TimerEvent&),
110  T *obj)
111 {
113  new TypedTimerImpl<T>(nh, period, callback, obj));
114 }
115 
116 inline
118 {
119  impl_ = other.impl_;
120  return *this;
121 }
122 
123 inline
125 {
126  return impl_->desiredPeriod();
127 }
128 
129 inline
131 {
132  return 1.0 / desiredPeriod().toSec();
133 }
134 
135 inline
137 {
138  return impl_->resetStatistics();
139 }
140 
141 inline
142 size_t Timer::ticks() const
143 {
144  return impl_->ticks();
145 }
146 
147 inline
149 {
150  return impl_->meanFrequencyHz();
151 }
152 
153 inline
155 {
156  return impl_->meanPeriod();
157 }
158 
159 inline
161 {
162  return impl_->minPeriod();
163 }
164 
165 inline
167 {
168  return impl_->maxPeriod();
169 }
170 
171 inline
173 {
174  return impl_->meanPeriod().toNSec() / 1000000.0;
175 }
176 
177 inline
179 {
180  return impl_->minPeriod().toNSec() / 1000000.0;
181 }
182 
183 inline
185 {
186  return impl_->maxPeriod().toNSec() / 1000000.0;
187 }
188 
189 inline
191 {
192  return impl_->meanDuration();
193 }
194 
195 inline
197 {
198  return impl_->minDuration();
199 }
200 
201 inline
203 {
204  return impl_->maxDuration();
205 }
206 
207 inline
209 {
210  return impl_->meanDuration().toNSec() / 1000.0;
211 }
212 
213 inline
215 {
216  return impl_->minDuration().toNSec() / 1000.0;
217 }
218 
219 inline
221 {
222  return impl_->maxDuration().toNSec() / 1000.0;
223 }
224 
225 
226 
227 inline
229  const std::string &name,
230  int flags)
231 {
232  // Alias a type for easier access to DiagnosticStatus enumerations.
233  // typedef diagnostic_msgs::DiagnosticStatus DS;
234 
235  // todo(anyone): Add an optional limit to set a warning or error
236  // some critical measurement crosses as threshold. Big ones are
237  // probably frequency dropping too low and duration getting too
238  // large.
239 
240  if (flags & DIAG_COUNT) {
241  status.addf(name + " ticks", "%d", ticks());
242  }
243 
244  if (flags & DIAG_RATE) {
245  if (ticks() < 2) {
246  status.add(
247  name + " rates",
248  "min period: N/A ms, mean frequency: N/A hz, max period: N/A ms");
249  } else {
250  status.addf(
251  name + " rates",
252  "min period: %.2f ms, mean frequency: %.2f hz, max period: %.2f ms",
254  meanFrequencyHz(),
256  }
257  }
258 
259  if (flags & DIAG_DURATION) {
260  if (ticks() < 1) {
261  status.add(name + " duration",
262  "min: N/A us, mean: N/A us, max: N/A us");
263  } else {
264  status.addf(name + " duration",
265  "min: %.2f us, mean: %.2f us, max: %.2f us",
269  }
270  }
271 }
272 } // namespace swri
273 #endif // SWRI_ROSCPP_TIMER_H_
swri::Timer::maxDurationMicroseconds
double maxDurationMicroseconds() const
Definition: timer.h:220
swri::Timer::ticks
size_t ticks() const
Definition: timer.h:142
swri::Timer::Timer
Timer()
Definition: timer.h:98
node_handle.h
swri::Timer::DIAG_DURATION
@ DIAG_DURATION
Definition: timer.h:85
swri::Timer::DIAG_RATE
@ DIAG_RATE
Definition: timer.h:84
swri::Timer::minDuration
ros::WallDuration minDuration() const
Definition: timer.h:196
boost::shared_ptr
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
swri::Timer::minPeriodMilliseconds
double minPeriodMilliseconds() const
Definition: timer.h:178
swri::Timer::meanFrequencyHz
double meanFrequencyHz() const
Definition: timer.h:148
swri::Timer::minPeriod
ros::Duration minPeriod() const
Definition: timer.h:160
swri::Timer::resetStatistics
void resetStatistics()
Definition: timer.h:136
swri::TypedTimerImpl
Definition: timer_impl.h:181
swri::Timer::meanDuration
ros::WallDuration meanDuration() const
Definition: timer.h:190
swri::TimerImpl
Definition: timer_impl.h:35
swri::Timer::desiredPeriod
ros::Duration desiredPeriod() const
Definition: timer.h:124
swri::Timer::maxDuration
ros::WallDuration maxDuration() const
Definition: timer.h:202
swri::Timer::appendDiagnostics
void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)
Definition: timer.h:228
swri::Timer::maxPeriod
ros::Duration maxPeriod() const
Definition: timer.h:166
swri::Timer::DIAG_ALL
@ DIAG_ALL
Definition: timer.h:87
swri::Timer::desiredFrequency
double desiredFrequency() const
Definition: timer.h:130
swri::Timer::meanPeriodMilliseconds
double meanPeriodMilliseconds() const
Definition: timer.h:172
DiagnosticStatusWrapper.h
swri::Timer::maxPeriodMilliseconds
double maxPeriodMilliseconds() const
Definition: timer.h:184
ros::TimerEvent
swri::Timer::operator=
Timer & operator=(const Timer &other)
Definition: timer.h:117
swri::Timer::meanPeriod
ros::Duration meanPeriod() const
Definition: timer.h:154
timer_impl.h
swri::Timer::DIAG_COUNT
@ DIAG_COUNT
Definition: timer.h:83
diagnostic_updater::DiagnosticStatusWrapper::addf
void addf(const std::string &key, const char *format,...)
swri
Definition: dynamic_parameters.h:51
diagnostic_updater::DiagnosticStatusWrapper
swri::Timer::impl_
boost::shared_ptr< TimerImpl > impl_
Definition: timer.h:41
swri::Timer::DIAGNOSTIC_FLAGS
DIAGNOSTIC_FLAGS
Definition: timer.h:82
DurationBase< Duration >::toSec
double toSec() const
ros::WallDuration
swri::Timer::meanDurationMicroseconds
double meanDurationMicroseconds() const
Definition: timer.h:208
ros::Duration
swri::Timer::DIAG_MOST
@ DIAG_MOST
Definition: timer.h:88
service_splitter.name
string name
Definition: service_splitter.py:68
ros::NodeHandle
swri::Timer::minDurationMicroseconds
double minDurationMicroseconds() const
Definition: timer.h:214
swri::Timer
Definition: timer.h:38


swri_roscpp
Author(s): P. J. Reed
autogenerated on Fri Aug 2 2024 08:39:15