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 /* Author Ioan Sucan */
36 
37 #ifndef OMPL_TOOLS_DEBUG_PROFILER_
38 #define OMPL_TOOLS_DEBUG_PROFILER_
39 
40 #ifndef ENABLE_PROFILING
41 
45 #ifdef NDEBUG
46 #define ENABLE_PROFILING 0
47 #else
48 #define ENABLE_PROFILING 1
49 #endif
50 
51 #endif
52 
53 #if ENABLE_PROFILING
54 
55 #include <map>
56 #include <string>
57 #include <iostream>
58 #include <thread>
59 #include <mutex>
60 
61 #include "ompl/util/Time.h"
62 
63 namespace ompl
64 {
65  namespace tools
66  {
72  class Profiler
73  {
74  public:
75  // non-copyable
76  Profiler(const Profiler &) = delete;
77  Profiler &operator=(const Profiler &) = delete;
78 
82  {
83  public:
85  ScopedBlock(const std::string &name, Profiler &prof = Profiler::Instance()) : name_(name), prof_(prof)
86  {
87  prof_.begin(name);
88  }
89 
90  ~ScopedBlock()
91  {
92  prof_.end(name_);
93  }
94 
95  private:
96  std::string name_;
97  Profiler &prof_;
98  };
99 
104  {
105  public:
107  ScopedStart(Profiler &prof = Profiler::Instance()) : prof_(prof), wasRunning_(prof_.running())
108  {
109  if (!wasRunning_)
110  prof_.start();
111  }
112 
113  ~ScopedStart()
114  {
115  if (!wasRunning_)
116  prof_.stop();
117  }
118 
119  private:
120  Profiler &prof_;
121  bool wasRunning_;
122  };
123 
125  static Profiler &Instance();
126 
129  Profiler(bool printOnDestroy = false, bool autoStart = false)
130  : running_(false), printOnDestroy_(printOnDestroy)
131  {
132  if (autoStart)
133  start();
134  }
135 
138  {
139  if (printOnDestroy_ && !data_.empty())
140  status();
141  }
142 
144  static void Start()
145  {
146  Instance().start();
147  }
148 
150  static void Stop()
151  {
152  Instance().stop();
153  }
154 
156  static void Clear()
157  {
158  Instance().clear();
159  }
160 
162  void start();
163 
165  void stop();
166 
168  void clear();
169 
171  static void Event(const std::string &name, const unsigned int times = 1)
172  {
173  Instance().event(name, times);
174  }
175 
177  void event(const std::string &name, const unsigned int times = 1);
178 
180  static void Average(const std::string &name, const double value)
181  {
182  Instance().average(name, value);
183  }
184 
186  void average(const std::string &name, const double value);
187 
189  static void Begin(const std::string &name)
190  {
191  Instance().begin(name);
192  }
193 
195  static void End(const std::string &name)
196  {
197  Instance().end(name);
198  }
199 
201  void begin(const std::string &name);
202 
204  void end(const std::string &name);
205 
209  static void Status(std::ostream &out = std::cout, bool merge = true)
210  {
211  Instance().status(out, merge);
212  }
213 
217  void status(std::ostream &out = std::cout, bool merge = true);
218 
221  static void Console()
222  {
223  Instance().console();
224  }
225 
228  void console();
229 
231  bool running() const
232  {
233  return running_;
234  }
235 
237  static bool Running()
238  {
239  return Instance().running();
240  }
241 
242  private:
244  struct TimeInfo
245  {
246  TimeInfo()
247  : total(time::seconds(0.)), shortest(time::duration::max()), longest(time::duration::min()), parts(0)
248  {
249  }
250 
252  time::duration total;
253 
255  time::duration shortest;
256 
258  time::duration longest;
259 
261  unsigned long int parts;
262 
265 
267  void set()
268  {
269  start = time::now();
270  }
271 
273  void update()
274  {
275  const time::duration &dt = time::now() - start;
276  if (dt > longest)
277  longest = dt;
278  if (dt < shortest)
279  shortest = dt;
280  total = total + dt;
281  ++parts;
282  }
283  };
284 
286  struct AvgInfo
287  {
289  double total;
290 
292  double totalSqr;
293 
295  unsigned long int parts;
296  };
297 
299  struct PerThread
300  {
302  std::map<std::string, unsigned long int> events;
303 
305  std::map<std::string, AvgInfo> avg;
306 
308  std::map<std::string, TimeInfo> time;
309  };
310 
311  void printThreadInfo(std::ostream &out, const PerThread &data);
312 
313  std::mutex lock_;
314  std::map<std::thread::id, PerThread> data_;
315  TimeInfo tinfo_;
316  bool running_;
317  bool printOnDestroy_;
318  };
319  }
320 }
321 
322 #else
323 
324 #include <string>
325 #include <iostream>
326 
327 /* If profiling is disabled, provide empty implementations for the
328  public functions */
329 namespace ompl
330 {
331  namespace tools
332  {
333  class Profiler
334  {
335  public:
336  class ScopedBlock
337  {
338  public:
339  ScopedBlock(const std::string &, Profiler & = Profiler::Instance())
340  {
341  }
342 
343  ~ScopedBlock() = default;
344  };
345 
346  class ScopedStart
347  {
348  public:
349  ScopedStart(Profiler & = Profiler::Instance())
350  {
351  }
352 
353  ~ScopedStart() = default;
354  };
355 
356  static Profiler &Instance();
357 
358  Profiler(bool = true, bool = true)
359  {
360  }
361 
362  ~Profiler() = default;
363 
364  static void Start()
365  {
366  }
367 
368  static void Stop()
369  {
370  }
371 
372  static void Clear()
373  {
374  }
375 
376  void start()
377  {
378  }
379 
380  void stop()
381  {
382  }
383 
384  void clear()
385  {
386  }
387 
388  static void Event(const std::string &, const unsigned int = 1)
389  {
390  }
391 
392  void event(const std::string &, const unsigned int = 1)
393  {
394  }
395 
396  static void Average(const std::string &, const double)
397  {
398  }
399 
400  void average(const std::string &, const double)
401  {
402  }
403 
404  static void Begin(const std::string &)
405  {
406  }
407 
408  static void End(const std::string &)
409  {
410  }
411 
412  void begin(const std::string &)
413  {
414  }
415 
416  void end(const std::string &)
417  {
418  }
419 
420  static void Status(std::ostream & = std::cout, bool = true)
421  {
422  }
423 
424  void status(std::ostream & = std::cout, bool = true)
425  {
426  }
427 
428  static void Console()
429  {
430  }
431 
432  void console()
433  {
434  }
435 
436  bool running() const
437  {
438  return false;
439  }
440 
441  static bool Running()
442  {
443  return false;
444  }
445  };
446  }
447 }
448 
449 #endif
450 
451 #endif
void end(const std::string &name)
Stop counting time for a specific chunk of code.
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition: Time.h:116
void start()
Start counting time.
static void Console()
Print the status of the profiled code chunks and events to the console (using msg::Console)
Definition: Profiler.h:221
static void Average(const std::string &name, const double value)
Maintain the average of a specific value.
Definition: Profiler.h:180
~Profiler()
Destructor.
Definition: Profiler.h:137
static bool Running()
Check if the profiler is counting time or not.
Definition: Profiler.h:237
point now()
Get the current time point.
Definition: Time.h:122
static void Clear()
Clear counted time and events.
Definition: Profiler.h:156
static void Stop()
Stop counting time.
Definition: Profiler.h:150
ScopedStart(Profiler &prof=Profiler::Instance())
Take as argument the profiler instance to operate on (prof)
Definition: Profiler.h:107
This is a simple thread-safe tool for counting time spent in various chunks of code....
Definition: Profiler.h:72
void console()
Print the status of the profiled code chunks and events to the console (using msg::Console)
void clear()
Clear counted time and events.
This instance will call Profiler::start() when constructed and Profiler::stop() when it goes out of s...
Definition: Profiler.h:103
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:209
void average(const std::string &name, const double value)
Maintain the average of a specific value.
std::chrono::system_clock::duration duration
Representation of a time duration.
Definition: Time.h:119
static void End(const std::string &name)
Stop counting time for a specific chunk of code.
Definition: Profiler.h:195
static void Start()
Start counting time.
Definition: Profiler.h:144
static void Begin(const std::string &name)
Begin counting time for a specific chunk of code.
Definition: Profiler.h:189
bool running() const
Check if the profiler is counting time or not.
Definition: Profiler.h:231
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 Profiler & Instance()
Return an instance of the class.
Definition: Profiler.cpp:40
void stop()
Stop counting time.
static void Event(const std::string &name, const unsigned int times=1)
Count a specific event for a number of times.
Definition: Profiler.h:171
ScopedBlock(const std::string &name, Profiler &prof=Profiler::Instance())
Start counting time for the block named name of the profiler prof.
Definition: Profiler.h:85
This instance will call Profiler::begin() when constructed and Profiler::end() when it goes out of sc...
Definition: Profiler.h:81
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
void begin(const std::string &name)
Begin counting time for a specific chunk of code.
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:129