timer_impl.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_H_
30 #define SWRI_ROSCPP_H_
31 
32 namespace swri
33 {
34 class Timer;
35 class TimerImpl
36 {
37  protected:
40 
41  int ticks_;
42 
45 
49 
53 
54  void tickBegin()
55  {
57 
58  ros::Time now = ros::Time::now();
59  if (ticks_ > 0) {
60  ros::Duration period = now - tick_begin_normal_;
61  total_periods_ += period;
62 
63  if (ticks_ == 1) {
64  min_period_ = period;
65  max_period_ = period;
66  } else {
67  min_period_ = std::min(min_period_, period);
68  max_period_ = std::max(max_period_, period);
69  }
70  }
71  tick_begin_normal_ = now;
72  }
73 
74  void tickEnd()
75  {
76  ros::WallTime end_time_ = ros::WallTime::now();
77  ros::WallDuration duration = end_time_ - tick_begin_wall_;
78  total_durations_ += duration;
79  if (ticks_ == 0) {
80  min_duration_ = duration;
81  max_duration_ = duration;
82  } else {
83  min_duration_ = std::min(min_duration_, duration);
84  max_duration_ = std::max(max_duration_, duration);
85  }
86  ticks_++;
87  }
88 
89  public:
91  {
93  }
94 
95  virtual ~TimerImpl()
96  {
97 
98  }
99 
101  {
102  return desired_period_;
103  }
104 
106  {
107  ticks_ = 0;
108  }
109 
110  // The number of times the timer callback has been called.
111  size_t ticks() const
112  {
113  return ticks_;
114  }
115 
116  double meanFrequencyHz() const
117  {
118  if (ticks_ < 2) {
119  return 0.0;
120  } else {
121  return 1e9 / meanPeriod().toNSec();
122  }
123  }
124 
126  {
127  if (ticks_ < 2) {
128  return ros::DURATION_MAX;
129  } else {
130  return ros::Duration(total_periods_.toSec() / (ticks_ - 1));
131  }
132  }
133 
135  {
136  if (ticks_ < 2) {
137  return ros::DURATION_MAX;
138  } else {
139  return min_period_;
140  }
141  }
142 
144  {
145  if (ticks_ < 2) {
146  return ros::DURATION_MAX;
147  } else {
148  return max_period_;
149  }
150  }
151 
153  {
154  if (ticks_ == 0) {
155  return ros::WallDuration(0.0);
156  } else {
158  }
159  }
160 
162  {
163  if (ticks_ == 0) {
164  return ros::WallDuration(0.0);
165  } else {
166  return min_duration_;
167  }
168  }
169 
171  {
172  if (ticks_ == 0) {
173  return ros::WallDuration(0.0);
174  } else {
175  return max_duration_;
176  }
177  }
178 }; // class TimerImpl
179 
180 template<class T>
181 class TypedTimerImpl : public TimerImpl
182 {
183  T *obj_;
184  void (T::*callback_)(const ros::TimerEvent &);
185 
186  public:
188  ros::NodeHandle &nh,
189  ros::Duration period,
190  void(T::*callback)(const ros::TimerEvent&),
191  T *obj)
192  {
193  callback_ = callback;
194  obj_ = obj;
195 
196  desired_period_ = period;
197  timer_ = nh.createTimer(period,
199  this);
200  }
201 
202  void handleTimer(const ros::TimerEvent &event)
203  {
204  tickBegin();
205  (obj_->*callback_)(event);
206  tickEnd();
207  }
208 }; // class TypedTimerImpl
209 } // namespace swri
210 #endif // SWRI_ROSCPP_H_
swri::TimerImpl::desiredPeriod
ros::Duration desiredPeriod() const
Definition: timer_impl.h:100
swri::TypedTimerImpl::obj_
T * obj_
Definition: timer_impl.h:183
swri::TimerImpl::maxDuration
ros::WallDuration maxDuration() const
Definition: timer_impl.h:170
swri::TimerImpl::meanPeriod
ros::Duration meanPeriod() const
Definition: timer_impl.h:125
swri::TypedTimerImpl
Definition: timer_impl.h:181
swri::TimerImpl::TimerImpl
TimerImpl()
Definition: timer_impl.h:90
swri::TimerImpl::resetStatistics
void resetStatistics()
Definition: timer_impl.h:105
ros::DURATION_MAX
const ROSTIME_DECL Duration DURATION_MAX
swri::TimerImpl::minDuration
ros::WallDuration minDuration() const
Definition: timer_impl.h:161
swri::TimerImpl
Definition: timer_impl.h:35
swri::TimerImpl::~TimerImpl
virtual ~TimerImpl()
Definition: timer_impl.h:95
swri::TimerImpl::max_period_
ros::Duration max_period_
Definition: timer_impl.h:48
swri::TypedTimerImpl::callback_
void(T::* callback_)(const ros::TimerEvent &)
Definition: timer_impl.h:184
swri::TimerImpl::minPeriod
ros::Duration minPeriod() const
Definition: timer_impl.h:134
swri::TimerImpl::total_durations_
ros::WallDuration total_durations_
Definition: timer_impl.h:50
swri::TimerImpl::meanFrequencyHz
double meanFrequencyHz() const
Definition: timer_impl.h:116
swri::TimerImpl::desired_period_
ros::Duration desired_period_
Definition: timer_impl.h:39
swri::TypedTimerImpl::handleTimer
void handleTimer(const ros::TimerEvent &event)
Definition: timer_impl.h:202
ros::WallTime::now
static WallTime now()
swri::TimerImpl::max_duration_
ros::WallDuration max_duration_
Definition: timer_impl.h:52
ros::TimerEvent
swri::TimerImpl::timer_
ros::Timer timer_
Definition: timer_impl.h:38
ros::WallTime
swri::TypedTimerImpl::TypedTimerImpl
TypedTimerImpl(ros::NodeHandle &nh, ros::Duration period, void(T::*callback)(const ros::TimerEvent &), T *obj)
Definition: timer_impl.h:187
swri::TimerImpl::min_duration_
ros::WallDuration min_duration_
Definition: timer_impl.h:51
ros::Time
DurationBase< Duration >::toNSec
int64_t toNSec() const
swri::TimerImpl::min_period_
ros::Duration min_period_
Definition: timer_impl.h:47
swri::TimerImpl::maxPeriod
ros::Duration maxPeriod() const
Definition: timer_impl.h:143
swri::TimerImpl::tickEnd
void tickEnd()
Definition: timer_impl.h:74
swri
Definition: dynamic_parameters.h:51
swri::TimerImpl::total_periods_
ros::Duration total_periods_
Definition: timer_impl.h:46
swri::TimerImpl::tick_begin_normal_
ros::Time tick_begin_normal_
Definition: timer_impl.h:44
swri::TimerImpl::ticks_
int ticks_
Definition: timer_impl.h:41
swri::TimerImpl::meanDuration
ros::WallDuration meanDuration() const
Definition: timer_impl.h:152
DurationBase< Duration >::toSec
double toSec() const
ros::WallDuration
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
swri::TimerImpl::tickBegin
void tickBegin()
Definition: timer_impl.h:54
ros::Duration
ros::Timer
ros::NodeHandle
swri::TimerImpl::ticks
size_t ticks() const
Definition: timer_impl.h:111
ros::Time::now
static Time now()
swri::TimerImpl::tick_begin_wall_
ros::WallTime tick_begin_wall_
Definition: timer_impl.h:43


swri_roscpp
Author(s): P. J. Reed
autogenerated on Thu Jun 6 2024 02:33:09