All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends
Profiler.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 
36 /* Author Ioan Sucan */
37 
38 #ifndef OMPL_UTIL_PROFILER_
39 #define OMPL_UTIL_PROFILER_
40 
41 #define ENABLE_PROFILING 1
42 
43 #ifndef ENABLE_PROFILING
44 
48 # ifdef NDEBUG
49 # define ENABLE_PROFILING 0
50 # else
51 # define ENABLE_PROFILING 1
52 # endif
53 
54 #endif
55 
56 #if ENABLE_PROFILING
57 
58 #include <map>
59 #include <string>
60 #include <iostream>
61 #include <boost/thread.hpp>
62 #include <boost/noncopyable.hpp>
63 
64 #include "ompl/util/Time.h"
65 
66 namespace ompl
67 {
68 
69  namespace tools
70  {
71 
77  class Profiler : private boost::noncopyable
78  {
79  public:
80 
83  {
84  public:
86  ScopedBlock(const std::string &name, Profiler &prof = Profiler::Instance()) : name_(name), prof_(prof)
87  {
88  prof_.begin(name);
89  }
90 
91  ~ScopedBlock(void)
92  {
93  prof_.end(name_);
94  }
95 
96  private:
97 
98  std::string name_;
99  Profiler &prof_;
100  };
101 
105  {
106  public:
107 
109  ScopedStart(Profiler &prof = Profiler::Instance()) : prof_(prof), wasRunning_(prof_.running())
110  {
111  if (!wasRunning_)
112  prof_.start();
113  }
114 
115  ~ScopedStart(void)
116  {
117  if (!wasRunning_)
118  prof_.stop();
119  }
120 
121  private:
122 
123  Profiler &prof_;
124  bool wasRunning_;
125  };
126 
128  static Profiler& Instance(void);
129 
132  Profiler(bool printOnDestroy = false, bool autoStart = false) : running_(false), printOnDestroy_(printOnDestroy)
133  {
134  if (autoStart)
135  start();
136  }
137 
139  ~Profiler(void)
140  {
141  if (printOnDestroy_ && !data_.empty())
142  status();
143  }
144 
146  static void Start(void)
147  {
148  Instance().start();
149  }
150 
152  static void Stop(void)
153  {
154  Instance().stop();
155  }
156 
158  static void Clear(void)
159  {
160  Instance().clear();
161  }
162 
164  void start(void);
165 
167  void stop(void);
168 
170  void clear(void);
171 
173  static void Event(const std::string& name, const unsigned int times = 1)
174  {
175  Instance().event(name, times);
176  }
177 
179  void event(const std::string &name, const unsigned int times = 1);
180 
182  static void Average(const std::string& name, const double value)
183  {
184  Instance().average(name, value);
185  }
186 
188  void average(const std::string &name, const double value);
189 
191  static void Begin(const std::string &name)
192  {
193  Instance().begin(name);
194  }
195 
197  static void End(const std::string &name)
198  {
199  Instance().end(name);
200  }
201 
203  void begin(const std::string &name);
204 
206  void end(const std::string &name);
207 
211  static void Status(std::ostream &out = std::cout, bool merge = true)
212  {
213  Instance().status(out, merge);
214  }
215 
219  void status(std::ostream &out = std::cout, bool merge = true);
220 
223  static void Console(void)
224  {
225  Instance().console();
226  }
227 
230  void console(void);
231 
233  bool running(void) const
234  {
235  return running_;
236  }
237 
239  static bool Running(void)
240  {
241  return Instance().running();
242  }
243 
244  private:
245 
247  struct TimeInfo
248  {
249  TimeInfo(void) : total(0, 0, 0, 0), shortest(boost::posix_time::pos_infin), longest(boost::posix_time::neg_infin), parts(0)
250  {
251  }
252 
254  time::duration total;
255 
257  time::duration shortest;
258 
260  time::duration longest;
261 
263  unsigned long int parts;
264 
267 
269  void set(void)
270  {
271  start = time::now();
272  }
273 
275  void update(void)
276  {
277  const time::duration &dt = time::now() - start;
278  if (dt > longest)
279  longest = dt;
280  if (dt < shortest)
281  shortest = dt;
282  total = total + dt;
283  ++parts;
284  }
285  };
286 
288  struct AvgInfo
289  {
291  double total;
292 
294  double totalSqr;
295 
297  unsigned long int parts;
298  };
299 
301  struct PerThread
302  {
304  std::map<std::string, unsigned long int> events;
305 
307  std::map<std::string, AvgInfo> avg;
308 
310  std::map<std::string, TimeInfo> time;
311  };
312 
313  void printThreadInfo(std::ostream &out, const PerThread &data);
314 
315  boost::mutex lock_;
316  std::map<boost::thread::id, PerThread> data_;
317  TimeInfo tinfo_;
318  bool running_;
319  bool printOnDestroy_;
320 
321  };
322  }
323 }
324 
325 #else
326 
327 #include <string>
328 #include <iostream>
329 
330 /* If profiling is disabled, provide empty implementations for the
331  public functions */
332 namespace ompl
333 {
334 
335  namespace tools
336  {
337 
338  class Profiler
339  {
340  public:
341 
342  class ScopedBlock
343  {
344  public:
345 
346  ScopedBlock(const std::string &, Profiler & = Profiler::Instance())
347  {
348  }
349 
350  ~ScopedBlock(void)
351  {
352  }
353  };
354 
355  class ScopedStart
356  {
357  public:
358 
360  {
361  }
362 
363  ~ScopedStart(void)
364  {
365  }
366  };
367 
368  static Profiler& Instance(void);
369 
370  Profiler(bool = true, bool = true)
371  {
372  }
373 
374  ~Profiler(void)
375  {
376  }
377 
378  static void Start(void)
379  {
380  }
381 
382  static void Stop(void)
383  {
384  }
385 
386  static void Clear(void)
387  {
388  }
389 
390  void start(void)
391  {
392  }
393 
394  void stop(void)
395  {
396  }
397 
398  void clear(void)
399  {
400  }
401 
402  static void Event(const std::string&, const unsigned int = 1)
403  {
404  }
405 
406  void event(const std::string &, const unsigned int = 1)
407  {
408  }
409 
410  static void Average(const std::string&, const double)
411  {
412  }
413 
414  void average(const std::string &, const double)
415  {
416  }
417 
418  static void Begin(const std::string &)
419  {
420  }
421 
422  static void End(const std::string &)
423  {
424  }
425 
426  void begin(const std::string &)
427  {
428  }
429 
430  void end(const std::string &)
431  {
432  }
433 
434  static void Status(std::ostream & = std::cout, bool = true)
435  {
436  }
437 
438  void status(std::ostream & = std::cout, bool = true)
439  {
440  }
441 
442  static void Console(void)
443  {
444  }
445 
446  void console(void)
447  {
448  }
449 
450  bool running(void) const
451  {
452  return false;
453  }
454 
455  static bool Running(void)
456  {
457  return false;
458  }
459  };
460  }
461 }
462 
463 #endif
464 
465 #endif
static bool Running(void)
Check if the profiler is counting time or not.
Definition: Profiler.h:239
static void Event(const std::string &name, const unsigned int times=1)
Count a specific event for a number of times.
Definition: Profiler.h:173
static void Average(const std::string &name, const double value)
Maintain the average of a specific value.
Definition: Profiler.h:182
static void End(const std::string &name)
Stop counting time for a specific chunk of code.
Definition: Profiler.h:197
boost::posix_time::time_duration duration
Representation of a time duration.
Definition: Time.h:53
void begin(const std::string &name)
Begin counting time for a specific chunk of code.
bool running(void) const
Check if the profiler is counting time or not.
Definition: Profiler.h:233
void start(void)
Start counting time.
void end(const std::string &name)
Stop counting time for a specific chunk of code.
void status(std::ostream &out=std::cout, bool merge=true)
Print the status of the profiled code chunks and events. Optionally, computation done by different th...
static void Console(void)
Print the status of the profiled code chunks and events to the console (using msg::Console) ...
Definition: Profiler.h:223
static void Start(void)
Start counting time.
Definition: Profiler.h:146
void event(const std::string &name, const unsigned int times=1)
Count a specific event for a number of times.
Profiler(bool printOnDestroy=false, bool autoStart=false)
Constructor. It is allowed to separately instantiate this class (not only as a singleton) ...
Definition: Profiler.h:132
ScopedBlock(const std::string &name, Profiler &prof=Profiler::Instance())
Start counting time for the block named name of the profiler prof.
Definition: Profiler.h:86
static void Stop(void)
Stop counting time.
Definition: Profiler.h:152
boost::posix_time::ptime point
Representation of a point in time.
Definition: Time.h:50
static void Status(std::ostream &out=std::cout, bool merge=true)
Print the status of the profiled code chunks and events. Optionally, computation done by different th...
Definition: Profiler.h:211
static void Clear(void)
Clear counted time and events.
Definition: Profiler.h:158
void console(void)
Print the status of the profiled code chunks and events to the console (using msg::Console) ...
static void Begin(const std::string &name)
Begin counting time for a specific chunk of code.
Definition: Profiler.h:191
static Profiler & Instance(void)
Return an instance of the class.
Definition: Profiler.cpp:40
This is a simple thread-safe tool for counting time spent in various chunks of code. This is different from external profiling tools in that it allows the user to count time spent in various bits of code (sub-function granularity) or count how many times certain pieces of code are executed.
Definition: Profiler.h:77
~Profiler(void)
Destructor.
Definition: Profiler.h:139
This instance will call Profiler::start() when constructed and Profiler::stop() when it goes out of s...
Definition: Profiler.h:104
void average(const std::string &name, const double value)
Maintain the average of a specific value.
void clear(void)
Clear counted time and events.
void stop(void)
Stop counting time.
This instance will call Profiler::begin() when constructed and Profiler::end() when it goes out of sc...
Definition: Profiler.h:82
point now(void)
Get the current time point.
Definition: Time.h:56
ScopedStart(Profiler &prof=Profiler::Instance())
Take as argument the profiler instance to operate on (prof)
Definition: Profiler.h:109