timer.h
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2015, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 #ifndef SWRI_ROSCPP_TIMER_H_
00030 #define SWRI_ROSCPP_TIMER_H_
00031 
00032 #include <ros/node_handle.h>
00033 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00034 #include <swri_roscpp/timer_impl.h>
00035 
00036 namespace swri
00037 {
00038 class Timer
00039 {
00040  private:
00041   boost::shared_ptr<TimerImpl> impl_;
00042 
00043  public:
00044   Timer();
00045 
00046   template<class T>
00047   Timer(ros::NodeHandle &nh,
00048         ros::Duration period,
00049         void(T::*callback)(const ros::TimerEvent&),
00050         T *obj);
00051 
00052   Timer& operator=(const Timer &other);
00053 
00054   ros::Duration desiredPeriod() const;
00055   double desiredFrequency() const;
00056   
00057   void resetStatistics();
00058 
00059   // The number of times the timer callback has been called.
00060   size_t ticks() const;
00061 
00062   // Frequency/Period of the timer callbacks.
00063   double meanFrequencyHz() const;
00064   ros::Duration meanPeriod() const;
00065   ros::Duration minPeriod() const;
00066   ros::Duration maxPeriod() const;
00067   double meanPeriodMilliseconds() const;
00068   double minPeriodMilliseconds() const;
00069   double maxPeriodMilliseconds() const;
00070 
00071   // Average duration of the timer callback.  These are tracked as
00072   // wall durations because they are typically used as a rough profile
00073   // of how long the callback takes to execute which is independent of
00074   // simulated time.
00075   ros::WallDuration meanDuration() const;
00076   ros::WallDuration minDuration() const;
00077   ros::WallDuration maxDuration() const;
00078   double meanDurationMicroseconds() const;
00079   double minDurationMicroseconds() const;
00080   double maxDurationMicroseconds() const;
00081 
00082   enum DIAGNOSTIC_FLAGS {
00083     DIAG_COUNT    = 1 << 0,
00084     DIAG_RATE     = 1 << 1,
00085     DIAG_DURATION = 1 << 2,
00086 
00087     DIAG_ALL      = ~0,
00088     DIAG_MOST     = DIAG_ALL ^ DIAG_COUNT
00089   };
00090 
00091   void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status,
00092                          const std::string &name,
00093                          const int flags);
00094 };  // class Timer
00095 
00096 
00097 inline
00098 Timer::Timer()
00099 {
00100   // Setup an empty implementation so that we can assume impl_ is
00101   // non-null and avoid a lot of unnecessary NULL checks.
00102   impl_ = boost::shared_ptr<TimerImpl>(new TimerImpl());
00103 }
00104 
00105 template<class T>
00106 inline
00107 Timer::Timer(ros::NodeHandle &nh,
00108              ros::Duration period,
00109              void(T::*callback)(const ros::TimerEvent&),
00110              T *obj)
00111 {
00112   impl_ = boost::shared_ptr<TimerImpl>(
00113     new TypedTimerImpl<T>(nh, period, callback, obj));
00114 }
00115 
00116 inline
00117 Timer& Timer::operator=(const Timer &other)
00118 {
00119   impl_ = other.impl_;
00120   return *this;
00121 }
00122 
00123 inline
00124 ros::Duration Timer::desiredPeriod() const
00125 {
00126   return impl_->desiredPeriod();
00127 }
00128 
00129 inline
00130 double Timer::desiredFrequency() const
00131 {
00132   return 1.0 / desiredPeriod().toSec();
00133 }
00134 
00135 inline
00136 void Timer::resetStatistics()
00137 {
00138   return impl_->resetStatistics();
00139 }
00140 
00141 inline
00142 size_t Timer::ticks() const
00143 {
00144   return impl_->ticks();
00145 }
00146 
00147 inline
00148 double Timer::meanFrequencyHz() const
00149 {
00150   return impl_->meanFrequencyHz();
00151 }
00152 
00153 inline
00154 ros::Duration Timer::meanPeriod() const
00155 {
00156   return impl_->meanPeriod();
00157 }
00158 
00159 inline
00160 ros::Duration Timer::minPeriod() const
00161 {
00162   return impl_->minPeriod();
00163 }
00164 
00165 inline
00166 ros::Duration Timer::maxPeriod() const
00167 {
00168   return impl_->maxPeriod();
00169 }
00170 
00171 inline
00172 double Timer::meanPeriodMilliseconds() const
00173 {
00174   return impl_->meanPeriod().toNSec() / 1000000.0;
00175 }
00176 
00177 inline
00178 double Timer::minPeriodMilliseconds() const
00179 {
00180   return impl_->minPeriod().toNSec() / 1000000.0;
00181 }
00182 
00183 inline
00184 double Timer::maxPeriodMilliseconds() const
00185 {
00186   return impl_->maxPeriod().toNSec() / 1000000.0;
00187 }
00188 
00189 inline
00190 ros::WallDuration Timer::meanDuration() const
00191 {
00192   return impl_->meanDuration();
00193 }
00194 
00195 inline
00196 ros::WallDuration Timer::minDuration() const
00197 {
00198   return impl_->minDuration();
00199 }
00200 
00201 inline
00202 ros::WallDuration Timer::maxDuration() const
00203 {
00204   return impl_->maxDuration();
00205 }
00206 
00207 inline
00208 double Timer::meanDurationMicroseconds() const
00209 {
00210   return impl_->meanDuration().toNSec() / 1000.0;
00211 }
00212 
00213 inline
00214 double Timer::minDurationMicroseconds() const
00215 {
00216   return impl_->minDuration().toNSec() / 1000.0;
00217 }
00218 
00219 inline
00220 double Timer::maxDurationMicroseconds() const
00221 {
00222   return impl_->maxDuration().toNSec() / 1000.0;
00223 }
00224 
00225 
00226 
00227 inline
00228 void Timer::appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status,
00229                               const std::string &name,
00230                               int flags)
00231 {
00232   // Alias a type for easier access to DiagnosticStatus enumerations.
00233   // typedef diagnostic_msgs::DiagnosticStatus DS;
00234 
00235   // todo(anyone): Add an optional limit to set a warning or error
00236   // some critical measurement crosses as threshold.  Big ones are
00237   // probably frequency dropping too low and duration getting too
00238   // large.
00239 
00240   if (flags & DIAG_COUNT) {
00241     status.addf(name + " ticks", "%d", ticks());
00242   }
00243 
00244   if (flags & DIAG_RATE) {
00245     if (ticks() < 2) {
00246     status.add(
00247       name + " rates",
00248       "min period: N/A ms, mean frequency: N/A hz, max period: N/A ms");
00249     } else {
00250       status.addf(
00251         name + " rates",
00252         "min period: %.2f ms, mean frequency: %.2f hz, max period: %.2f ms",
00253         minPeriodMilliseconds(),
00254         meanFrequencyHz(),
00255         maxPeriodMilliseconds());
00256     }
00257   }
00258 
00259   if (flags & DIAG_DURATION) {
00260     if (ticks() < 1) {
00261       status.add(name + " duration",
00262                  "min: N/A us, mean: N/A us, max: N/A us");
00263     } else {
00264       status.addf(name + " duration",
00265                   "min: %.2f us, mean: %.2f us, max: %.2f us",
00266                   minDurationMicroseconds(),
00267                   meanDurationMicroseconds(),
00268                   maxDurationMicroseconds());
00269     }
00270   }
00271 }
00272 }  // namespace swri
00273 #endif  // SWRI_ROSCPP_TIMER_H_


swri_roscpp
Author(s):
autogenerated on Tue Oct 3 2017 03:19:27