profiler.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
39 
40 namespace fcl {
41 namespace detail {
42 
43 //==============================================================================
45 {
46  static Profiler p(true, false);
47  return p;
48 }
49 
50 //==============================================================================
51 Profiler::Profiler(bool printOnDestroy, bool autoStart)
52  : running_(false), printOnDestroy_(printOnDestroy)
53 {
54  if (autoStart)
55  start();
56 }
57 
58 //==============================================================================
60 {
61  if (printOnDestroy_ && !data_.empty())
62  status();
63 }
64 
65 //==============================================================================
67 {
68  Instance().start();
69 }
70 
71 //==============================================================================
73 {
74  Instance().stop();
75 }
76 
77 //==============================================================================
79 {
80  Instance().clear();
81 }
82 
83 //==============================================================================
84 void Profiler::start(void)
85 {
86  lock_.lock();
87  if (!running_)
88  {
89  tinfo_.set();
90  running_ = true;
91  }
92  lock_.unlock();
93 }
94 
95 //==============================================================================
96 void Profiler::stop(void)
97 {
98  lock_.lock();
99  if (running_)
100  {
101  tinfo_.update();
102  running_ = false;
103  }
104  lock_.unlock();
105 }
106 
107 //==============================================================================
108 void Profiler::clear(void)
109 {
110  lock_.lock();
111  data_.clear();
112  tinfo_ = TimeInfo();
113  if (running_)
114  tinfo_.set();
115  lock_.unlock();
116 }
117 
118 //==============================================================================
119 void Profiler::Event(const std::string& name, const unsigned int times)
120 {
121  Instance().event(name, times);
122 }
123 
124 //==============================================================================
125 void Profiler::event(const std::string &name, const unsigned int times)
126 {
127  lock_.lock();
128  data_[std::this_thread::get_id()].events[name] += times;
129  lock_.unlock();
130 }
131 
132 //==============================================================================
133 void Profiler::Average(const std::string& name, const double value)
134 {
135  Instance().average(name, value);
136 }
137 
138 //==============================================================================
139 void Profiler::average(const std::string &name, const double value)
140 {
141  lock_.lock();
142  AvgInfo &a = data_[std::this_thread::get_id()].avg[name];
143  a.total += value;
144  a.totalSqr += value*value;
145  a.parts++;
146  lock_.unlock();
147 }
148 
149 //==============================================================================
150 void Profiler::Begin(const std::string& name)
151 {
152  Instance().begin(name);
153 }
154 
155 //==============================================================================
156 void Profiler::End(const std::string& name)
157 {
158  Instance().end(name);
159 }
160 
161 //==============================================================================
162 void Profiler::begin(const std::string &name)
163 {
164  lock_.lock();
165  data_[std::this_thread::get_id()].time[name].set();
166  lock_.unlock();
167 }
168 
169 //==============================================================================
170 void Profiler::end(const std::string &name)
171 {
172  lock_.lock();
173  data_[std::this_thread::get_id()].time[name].update();
174  lock_.unlock();
175 }
176 
177 //==============================================================================
178 void Profiler::Status(std::ostream& out, bool merge)
179 {
180  Instance().status(out, merge);
181 }
182 
183 //==============================================================================
184 void Profiler::status(std::ostream &out, bool merge)
185 {
186  stop();
187  lock_.lock();
188  printOnDestroy_ = false;
189 
190  out << std::endl;
191  out << " *** Profiling statistics. Total counted time : " << time::seconds(tinfo_.total) << " seconds" << std::endl;
192 
193  if (merge)
194  {
195  PerThread combined;
196  for (std::map<std::thread::id, PerThread>::const_iterator it = data_.begin() ; it != data_.end() ; ++it)
197  {
198  for (std::map<std::string, unsigned long int>::const_iterator iev = it->second.events.begin() ; iev != it->second.events.end(); ++iev)
199  combined.events[iev->first] += iev->second;
200  for (std::map<std::string, AvgInfo>::const_iterator iavg = it->second.avg.begin() ; iavg != it->second.avg.end(); ++iavg)
201  {
202  combined.avg[iavg->first].total += iavg->second.total;
203  combined.avg[iavg->first].totalSqr += iavg->second.totalSqr;
204  combined.avg[iavg->first].parts += iavg->second.parts;
205  }
206  for (std::map<std::string, TimeInfo>::const_iterator itm = it->second.time.begin() ; itm != it->second.time.end(); ++itm)
207  {
208  TimeInfo &tc = combined.time[itm->first];
209  tc.total = tc.total + itm->second.total;
210  tc.parts = tc.parts + itm->second.parts;
211  if (tc.shortest > itm->second.shortest)
212  tc.shortest = itm->second.shortest;
213  if (tc.longest < itm->second.longest)
214  tc.longest = itm->second.longest;
215  }
216  }
217  printThreadInfo(out, combined);
218  }
219  else
220  for (std::map<std::thread::id, PerThread>::const_iterator it = data_.begin() ; it != data_.end() ; ++it)
221  {
222  out << "Thread " << it->first << ":" << std::endl;
223  printThreadInfo(out, it->second);
224  }
225  lock_.unlock();
226 }
227 
228 //==============================================================================
229 bool Profiler::running() const
230 {
231  return running_;
232 }
233 
234 //==============================================================================
236 {
237  return Instance().running();
238 }
239 
240 //==============================================================================
241 struct FCL_EXPORT dataIntVal
242 {
243  std::string name;
244  unsigned long int value;
245 };
246 
247 //==============================================================================
248 struct FCL_EXPORT SortIntByValue
249 {
250  bool operator()(const dataIntVal &a, const dataIntVal &b) const
251  {
252  return a.value > b.value;
253  }
254 };
255 
256 //==============================================================================
257 struct FCL_EXPORT dataDoubleVal
258 {
259  std::string name;
260  double value;
261 };
262 
263 //==============================================================================
264 struct FCL_EXPORT SortDoubleByValue
265 {
266  bool operator()(const dataDoubleVal &a, const dataDoubleVal &b) const
267  {
268  return a.value > b.value;
269  }
270 };
271 
272 //==============================================================================
273 void Profiler::printThreadInfo(std::ostream &out, const PerThread &data)
274 {
275  double total = time::seconds(tinfo_.total);
276 
277  std::vector<detail::dataIntVal> events;
278  for (std::map<std::string, unsigned long int>::const_iterator iev = data.events.begin() ; iev != data.events.end() ; ++iev)
279  {
280  detail::dataIntVal next = {iev->first, iev->second};
281  events.push_back(next);
282  }
283  std::sort(events.begin(), events.end(), SortIntByValue());
284  if (!events.empty())
285  out << "Events:" << std::endl;
286  for (unsigned int i = 0 ; i < events.size() ; ++i)
287  out << events[i].name << ": " << events[i].value << std::endl;
288 
289  std::vector<detail::dataDoubleVal> avg;
290  for (std::map<std::string, AvgInfo>::const_iterator ia = data.avg.begin() ; ia != data.avg.end() ; ++ia)
291  {
292  detail::dataDoubleVal next = {ia->first, ia->second.total / (double)ia->second.parts};
293  avg.push_back(next);
294  }
295  std::sort(avg.begin(), avg.end(), SortDoubleByValue());
296  if (!avg.empty())
297  out << "Averages:" << std::endl;
298  for (unsigned int i = 0 ; i < avg.size() ; ++i)
299  {
300  const AvgInfo &a = data.avg.find(avg[i].name)->second;
301  out << avg[i].name << ": " << avg[i].value << " (stddev = " <<
302  std::sqrt(std::abs(a.totalSqr - (double)a.parts * avg[i].value * avg[i].value) / ((double)a.parts - 1.)) << ")" << std::endl;
303  }
304 
305  std::vector<detail::dataDoubleVal> time;
306 
307  for (std::map<std::string, TimeInfo>::const_iterator itm = data.time.begin() ; itm != data.time.end() ; ++itm)
308  {
309  detail::dataDoubleVal next = {itm->first, time::seconds(itm->second.total)};
310  time.push_back(next);
311  }
312 
313  std::sort(time.begin(), time.end(), detail::SortDoubleByValue());
314  if (!time.empty())
315  out << "Blocks of time:" << std::endl;
316 
317  double unaccounted = total;
318  for (unsigned int i = 0 ; i < time.size() ; ++i)
319  {
320  const TimeInfo &d = data.time.find(time[i].name)->second;
321 
322  double tS = time::seconds(d.shortest);
323  double tL = time::seconds(d.longest);
324  out << time[i].name << ": " << time[i].value << "s (" << (100.0 * time[i].value/total) << "%), ["
325  << tS << "s --> " << tL << " s], " << d.parts << " parts";
326  if (d.parts > 0)
327  out << ", " << (time::seconds(d.total) / (double)d.parts) << " s on average";
328  out << std::endl;
329  unaccounted -= time[i].value;
330  }
331  out << "Unaccounted time : " << unaccounted;
332  if (total > 0.0)
333  out << " (" << (100.0 * unaccounted / total) << " %)";
334  out << std::endl;
335 
336  out << std::endl;
337 }
338 
339 //==============================================================================
341  : total(time::seconds(0.)),
342  shortest(time::duration::max()),
343  longest(time::duration::min()),
344  parts(0)
345 {
346  // Do nothing
347 }
348 
349 //==============================================================================
351 {
352  start = time::now();
353 }
354 
355 //==============================================================================
357 {
358  const time::duration &dt = time::now() - start;
359 
360  if (dt > longest)
361  longest = dt;
362 
363  if (dt < shortest)
364  shortest = dt;
365 
366  total = total + dt;
367  ++parts;
368 }
369 
370 //==============================================================================
371 Profiler::ScopedStart::ScopedStart(Profiler& prof)
372  : prof_(prof), wasRunning_(prof_.running())
373 {
374  if (!wasRunning_)
375  prof_.start();
376 }
377 
378 //==============================================================================
379 Profiler::ScopedStart::~ScopedStart()
380 {
381  if (!wasRunning_)
382  prof_.stop();
383 }
384 
385 //==============================================================================
386 Profiler::ScopedBlock::ScopedBlock(const std::string& name, Profiler& prof)
387  : name_(name), prof_(prof)
388 {
389  prof_.begin(name);
390 }
391 
392 //==============================================================================
393 Profiler::ScopedBlock::~ScopedBlock()
394 {
395  prof_.end(name_);
396 }
397 
398 } // namespace detail
399 } // namespace fcl
time::point start
The point in time when counting time started.
std::chrono::system_clock::duration duration
Representation of a time duration.
Definition: time.h:55
FCL_EXPORT duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition: time.cpp:53
unsigned long int parts
Number of times a value was added to this structure.
time::duration shortest
The shortest counted time interval.
Information about time spent in a section of the code.
Main namespace.
void update(void)
Add the counted time to the total time.
Definition: profiler.cpp:356
std::map< std::string, unsigned long int > events
The stored events.
void clear(void)
Clear counted time and events.
Definition: profiler.cpp:108
static bool Running(void)
Check if the profiler is counting time or not.
Definition: profiler.cpp:235
unsigned long int parts
Number of times a chunk of time was added to this structure.
FCL_EXPORT point now(void)
Get the current time point.
Definition: time.cpp:47
static void Begin(const std::string &name)
Begin counting time for a specific chunk of code.
Definition: profiler.cpp:150
double total
The sum of the values to average.
EndPoint * next[3]
the next end point in the end point list
static void End(const std::string &name)
Stop counting time for a specific chunk of code.
Definition: profiler.cpp:156
unsigned long int value
Definition: profiler.cpp:244
Information maintained about averaged values.
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.cpp:178
static void Event(const std::string &name, const unsigned int times=1)
Count a specific event for a number of times.
Definition: profiler.cpp:119
static Profiler & Instance(void)
Return an instance of the class.
Definition: profiler.cpp:44
void average(const std::string &name, const double value)
Maintain the average of a specific value.
Definition: profiler.cpp:139
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.cpp:184
bool operator()(const dataDoubleVal &a, const dataDoubleVal &b) const
Definition: profiler.cpp:266
void event(const std::string &name, const unsigned int times=1)
Count a specific event for a number of times.
Definition: profiler.cpp:125
std::string name
time::duration longest
The longest counted time interval.
std::map< std::string, AvgInfo > avg
The stored averages.
bool running(void) const
Check if the profiler is counting time or not.
Definition: profiler.cpp:229
std::map< std::string, TimeInfo > time
The amount of time spent in various places.
void printThreadInfo(std::ostream &out, const PerThread &data)
Definition: profiler.cpp:273
static void Start(void)
Start counting time.
Definition: profiler.cpp:66
void stop(void)
Stop counting time.
Definition: profiler.cpp:96
~Profiler(void)
Destructor.
Definition: profiler.cpp:59
static T max(T x, T y)
Definition: svm.cpp:52
double totalSqr
The sub of squares of the values to average.
static void Clear(void)
Clear counted time and events.
Definition: profiler.cpp:78
Information to be maintained for each thread.
static T min(T x, T y)
Definition: svm.cpp:49
bool operator()(const dataIntVal &a, const dataIntVal &b) const
Definition: profiler.cpp:250
void end(const std::string &name)
Stop counting time for a specific chunk of code.
Definition: profiler.cpp:170
static void Average(const std::string &name, const double value)
Maintain the average of a specific value.
Definition: profiler.cpp:133
time::duration total
Total time counted.
void set(void)
Begin counting time.
Definition: profiler.cpp:350
void start(void)
Start counting time.
Definition: profiler.cpp:84
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.
void begin(const std::string &name)
Begin counting time for a specific chunk of code.
Definition: profiler.cpp:162
Profiler(const Profiler &)=delete
static void Stop(void)
Stop counting time.
Definition: profiler.cpp:72
std::map< std::thread::id, PerThread > data_


fcl_catkin
Author(s):
autogenerated on Thu Mar 23 2023 03:00:18