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 namespace tools
00067 {
00073 class Profiler : private boost::noncopyable
00074 {
00075 public:
00078   class ScopedBlock
00079   {
00080   public:
00082     ScopedBlock(const std::string& name, Profiler& prof = Profiler::Instance()) : name_(name), prof_(prof)
00083     {
00084       prof_.begin(name);
00085     }
00086 
00087     ~ScopedBlock(void)
00088     {
00089       prof_.end(name_);
00090     }
00091 
00092   private:
00093     std::string name_;
00094     Profiler& prof_;
00095   };
00096 
00099   class ScopedStart
00100   {
00101   public:
00103     ScopedStart(Profiler& prof = Profiler::Instance()) : prof_(prof), wasRunning_(prof_.running())
00104     {
00105       if (!wasRunning_)
00106         prof_.start();
00107     }
00108 
00109     ~ScopedStart(void)
00110     {
00111       if (!wasRunning_)
00112         prof_.stop();
00113     }
00114 
00115   private:
00116     Profiler& prof_;
00117     bool wasRunning_;
00118   };
00119 
00121   static Profiler& Instance(void);
00122 
00125   Profiler(bool printOnDestroy = false, bool autoStart = false) : running_(false), printOnDestroy_(printOnDestroy)
00126   {
00127     if (autoStart)
00128       start();
00129   }
00130 
00132   ~Profiler(void)
00133   {
00134     if (printOnDestroy_ && !data_.empty())
00135       status();
00136   }
00137 
00139   static void Start(void)
00140   {
00141     Instance().start();
00142   }
00143 
00145   static void Stop(void)
00146   {
00147     Instance().stop();
00148   }
00149 
00151   static void Clear(void)
00152   {
00153     Instance().clear();
00154   }
00155 
00157   void start(void);
00158 
00160   void stop(void);
00161 
00163   void clear(void);
00164 
00166   static void Event(const std::string& name, const unsigned int times = 1)
00167   {
00168     Instance().event(name, times);
00169   }
00170 
00172   void event(const std::string& name, const unsigned int times = 1);
00173 
00175   static void Average(const std::string& name, const double value)
00176   {
00177     Instance().average(name, value);
00178   }
00179 
00181   void average(const std::string& name, const double value);
00182 
00184   static void Begin(const std::string& name)
00185   {
00186     Instance().begin(name);
00187   }
00188 
00190   static void End(const std::string& name)
00191   {
00192     Instance().end(name);
00193   }
00194 
00196   void begin(const std::string& name);
00197 
00199   void end(const std::string& name);
00200 
00204   static void Status(std::ostream& out = std::cout, bool merge = true)
00205   {
00206     Instance().status(out, merge);
00207   }
00208 
00212   void status(std::ostream& out = std::cout, bool merge = true);
00213 
00216   static void Console(void)
00217   {
00218     Instance().console();
00219   }
00220 
00223   void console(void);
00224 
00226   bool running(void) const
00227   {
00228     return running_;
00229   }
00230 
00232   static bool Running(void)
00233   {
00234     return Instance().running();
00235   }
00236 
00237 private:
00239   struct TimeInfo
00240   {
00241     TimeInfo(void)
00242       : total(0, 0, 0, 0), shortest(boost::posix_time::pos_infin), longest(boost::posix_time::neg_infin), parts(0)
00243     {
00244     }
00245 
00247     boost::posix_time::time_duration total;
00248 
00250     boost::posix_time::time_duration shortest;
00251 
00253     boost::posix_time::time_duration longest;
00254 
00256     unsigned long int parts;
00257 
00259     boost::posix_time::ptime start;
00260 
00262     void set(void)
00263     {
00264       start = boost::posix_time::microsec_clock::universal_time();
00265     }
00266 
00268     void update(void)
00269     {
00270       const boost::posix_time::time_duration& dt = boost::posix_time::microsec_clock::universal_time() - start;
00271       if (dt > longest)
00272         longest = dt;
00273       if (dt < shortest)
00274         shortest = dt;
00275       total = total + dt;
00276       ++parts;
00277     }
00278   };
00279 
00281   struct AvgInfo
00282   {
00284     double total;
00285 
00287     double totalSqr;
00288 
00290     unsigned long int parts;
00291   };
00292 
00294   struct PerThread
00295   {
00297     std::map<std::string, unsigned long int> events;
00298 
00300     std::map<std::string, AvgInfo> avg;
00301 
00303     std::map<std::string, TimeInfo> time;
00304   };
00305 
00306   void printThreadInfo(std::ostream& out, const PerThread& data);
00307 
00308   boost::mutex lock_;
00309   std::map<boost::thread::id, PerThread> data_;
00310   TimeInfo tinfo_;
00311   bool running_;
00312   bool printOnDestroy_;
00313 };
00314 }
00315 }
00316 
00317 #else
00318 
00319 #include <string>
00320 #include <iostream>
00321 
00322 /* If profiling is disabled, provide empty implementations for the
00323    public functions */
00324 namespace moveit
00325 {
00326 namespace tools
00327 {
00328 class Profiler
00329 {
00330 public:
00331   class ScopedBlock
00332   {
00333   public:
00334     ScopedBlock(const std::string&, Profiler& = Profiler::Instance())
00335     {
00336     }
00337 
00338     ~ScopedBlock(void)
00339     {
00340     }
00341   };
00342 
00343   class ScopedStart
00344   {
00345   public:
00346     ScopedStart(Profiler& = Profiler::Instance())
00347     {
00348     }
00349 
00350     ~ScopedStart(void)
00351     {
00352     }
00353   };
00354 
00355   static Profiler& Instance(void);
00356 
00357   Profiler(bool = true, bool = true)
00358   {
00359   }
00360 
00361   ~Profiler(void)
00362   {
00363   }
00364 
00365   static void Start(void)
00366   {
00367   }
00368 
00369   static void Stop(void)
00370   {
00371   }
00372 
00373   static void Clear(void)
00374   {
00375   }
00376 
00377   void start(void)
00378   {
00379   }
00380 
00381   void stop(void)
00382   {
00383   }
00384 
00385   void clear(void)
00386   {
00387   }
00388 
00389   static void Event(const std::string&, const unsigned int = 1)
00390   {
00391   }
00392 
00393   void event(const std::string&, const unsigned int = 1)
00394   {
00395   }
00396 
00397   static void Average(const std::string&, const double)
00398   {
00399   }
00400 
00401   void average(const std::string&, const double)
00402   {
00403   }
00404 
00405   static void Begin(const std::string&)
00406   {
00407   }
00408 
00409   static void End(const std::string&)
00410   {
00411   }
00412 
00413   void begin(const std::string&)
00414   {
00415   }
00416 
00417   void end(const std::string&)
00418   {
00419   }
00420 
00421   static void Status(std::ostream& = std::cout, bool = true)
00422   {
00423   }
00424 
00425   void status(std::ostream& = std::cout, bool = true)
00426   {
00427   }
00428 
00429   static void Console(void)
00430   {
00431   }
00432 
00433   void console(void)
00434   {
00435   }
00436 
00437   bool running(void) const
00438   {
00439     return false;
00440   }
00441 
00442   static bool Running(void)
00443   {
00444     return false;
00445   }
00446 };
00447 }
00448 }
00449 
00450 #endif
00451 
00452 #endif


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Jul 24 2017 02:20:44