profiler.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan */
00036 
00037 #ifndef MOVEIT_PROFILER_
00038 #define MOVEIT_PROFILER_
00039 
00040 #define MOVEIT_ENABLE_PROFILING 1
00041 
00042 #ifndef MOVEIT_ENABLE_PROFILING
00043 
00047 #  ifdef NDEBUG
00048 #    define MOVEIT_ENABLE_PROFILING 0
00049 #  else
00050 #    define MOVEIT_ENABLE_PROFILING 1
00051 #  endif
00052 
00053 #endif
00054 
00055 #if MOVEIT_ENABLE_PROFILING
00056 
00057 #include <map>
00058 #include <string>
00059 #include <iostream>
00060 #include <boost/thread.hpp>
00061 #include <boost/noncopyable.hpp>
00062 #include <boost/date_time/posix_time/posix_time.hpp>
00063 
00064 namespace moveit
00065 {
00066 
00067 namespace tools
00068 {
00069 
00075 class Profiler : private boost::noncopyable
00076 {
00077 public:
00078 
00080   class ScopedBlock
00081   {
00082   public:
00084     ScopedBlock(const std::string &name, Profiler &prof = Profiler::Instance()) : name_(name), prof_(prof)
00085     {
00086       prof_.begin(name);
00087     }
00088 
00089     ~ScopedBlock(void)
00090     {
00091       prof_.end(name_);
00092     }
00093 
00094   private:
00095 
00096     std::string  name_;
00097     Profiler    &prof_;
00098   };
00099 
00102   class ScopedStart
00103   {
00104   public:
00105 
00107     ScopedStart(Profiler &prof = Profiler::Instance()) : prof_(prof), wasRunning_(prof_.running())
00108     {
00109       if (!wasRunning_)
00110         prof_.start();
00111     }
00112 
00113     ~ScopedStart(void)
00114     {
00115       if (!wasRunning_)
00116         prof_.stop();
00117     }
00118 
00119   private:
00120 
00121     Profiler &prof_;
00122     bool      wasRunning_;
00123   };
00124 
00126   static Profiler& Instance(void);
00127 
00130   Profiler(bool printOnDestroy = false, bool autoStart = false) : running_(false), printOnDestroy_(printOnDestroy)
00131   {
00132     if (autoStart)
00133       start();
00134   }
00135 
00137   ~Profiler(void)
00138   {
00139     if (printOnDestroy_ && !data_.empty())
00140       status();
00141   }
00142 
00144   static void Start(void)
00145   {
00146     Instance().start();
00147   }
00148 
00150   static void Stop(void)
00151   {
00152     Instance().stop();
00153   }
00154 
00156   static void Clear(void)
00157   {
00158     Instance().clear();
00159   }
00160 
00162   void start(void);
00163 
00165   void stop(void);
00166 
00168   void clear(void);
00169 
00171   static void Event(const std::string& name, const unsigned int times = 1)
00172   {
00173     Instance().event(name, times);
00174   }
00175 
00177   void event(const std::string &name, const unsigned int times = 1);
00178 
00180   static void Average(const std::string& name, const double value)
00181   {
00182     Instance().average(name, value);
00183   }
00184 
00186   void average(const std::string &name, const double value);
00187 
00189   static void Begin(const std::string &name)
00190   {
00191     Instance().begin(name);
00192   }
00193 
00195   static void End(const std::string &name)
00196   {
00197     Instance().end(name);
00198   }
00199 
00201   void begin(const std::string &name);
00202 
00204   void end(const std::string &name);
00205 
00209   static void Status(std::ostream &out = std::cout, bool merge = true)
00210   {
00211     Instance().status(out, merge);
00212   }
00213 
00217   void status(std::ostream &out = std::cout, bool merge = true);
00218 
00221   static void Console(void)
00222   {
00223     Instance().console();
00224   }
00225 
00228   void console(void);
00229 
00231   bool running(void) const
00232   {
00233     return running_;
00234   }
00235 
00237   static bool Running(void)
00238   {
00239     return Instance().running();
00240   }
00241 
00242 private:
00243 
00245   struct TimeInfo
00246   {
00247     TimeInfo(void) : total(0, 0, 0, 0), shortest(boost::posix_time::pos_infin), longest(boost::posix_time::neg_infin), parts(0)
00248     {
00249     }
00250 
00252     boost::posix_time::time_duration total;
00253 
00255     boost::posix_time::time_duration shortest;
00256 
00258     boost::posix_time::time_duration longest;
00259 
00261     unsigned long int parts;
00262 
00264     boost::posix_time::ptime start;
00265 
00267     void set(void)
00268     {
00269       start = boost::posix_time::microsec_clock::universal_time();
00270     }
00271 
00273     void update(void)
00274     {
00275       const boost::posix_time::time_duration &dt = boost::posix_time::microsec_clock::universal_time() - start;
00276       if (dt > longest)
00277         longest = dt;
00278       if (dt < shortest)
00279         shortest = dt;
00280       total = total + dt;
00281       ++parts;
00282     }
00283   };
00284 
00286   struct AvgInfo
00287   {
00289     double            total;
00290 
00292     double            totalSqr;
00293 
00295     unsigned long int parts;
00296   };
00297 
00299   struct PerThread
00300   {
00302     std::map<std::string, unsigned long int> events;
00303 
00305     std::map<std::string, AvgInfo>           avg;
00306 
00308     std::map<std::string, TimeInfo>          time;
00309   };
00310 
00311   void printThreadInfo(std::ostream &out, const PerThread &data);
00312 
00313   boost::mutex                           lock_;
00314   std::map<boost::thread::id, PerThread> data_;
00315   TimeInfo                               tinfo_;
00316   bool                                   running_;
00317   bool                                   printOnDestroy_;
00318 
00319 };
00320 }
00321 }
00322 
00323 #else
00324 
00325 #include <string>
00326 #include <iostream>
00327 
00328 /* If profiling is disabled, provide empty implementations for the
00329    public functions */
00330 namespace moveit
00331 {
00332 namespace tools
00333 {
00334 
00335 class Profiler
00336 {
00337 public:
00338 
00339   class ScopedBlock
00340   {
00341   public:
00342 
00343     ScopedBlock(const std::string &, Profiler & = Profiler::Instance())
00344     {
00345     }
00346 
00347     ~ScopedBlock(void)
00348     {
00349     }
00350   };
00351 
00352   class ScopedStart
00353   {
00354   public:
00355 
00356     ScopedStart(Profiler & = Profiler::Instance())
00357     {
00358     }
00359 
00360     ~ScopedStart(void)
00361     {
00362     }
00363   };
00364 
00365   static Profiler& Instance(void);
00366 
00367   Profiler(bool = true, bool = true)
00368   {
00369   }
00370 
00371   ~Profiler(void)
00372   {
00373   }
00374 
00375   static void Start(void)
00376   {
00377   }
00378 
00379   static void Stop(void)
00380   {
00381   }
00382 
00383   static void Clear(void)
00384   {
00385   }
00386 
00387   void start(void)
00388   {
00389   }
00390 
00391   void stop(void)
00392   {
00393   }
00394 
00395   void clear(void)
00396   {
00397   }
00398 
00399   static void Event(const std::string&, const unsigned int = 1)
00400   {
00401   }
00402 
00403   void event(const std::string &, const unsigned int = 1)
00404   {
00405   }
00406 
00407   static void Average(const std::string&, const double)
00408   {
00409   }
00410 
00411   void average(const std::string &, const double)
00412   {
00413   }
00414 
00415   static void Begin(const std::string &)
00416   {
00417   }
00418 
00419   static void End(const std::string &)
00420   {
00421   }
00422 
00423   void begin(const std::string &)
00424   {
00425   }
00426 
00427   void end(const std::string &)
00428   {
00429   }
00430 
00431   static void Status(std::ostream & = std::cout, bool = true)
00432   {
00433   }
00434 
00435   void status(std::ostream & = std::cout, bool = true)
00436   {
00437   }
00438 
00439   static void Console(void)
00440   {
00441   }
00442 
00443   void console(void)
00444   {
00445   }
00446 
00447   bool running(void) const
00448   {
00449     return false;
00450   }
00451 
00452   static bool Running(void)
00453   {
00454     return false;
00455   }
00456 };
00457 
00458 }
00459 }
00460 
00461 
00462 #endif
00463 
00464 #endif


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:53