profiler.cpp
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 #include "moveit/profiler/profiler.h"
00038 
00039 moveit::tools::Profiler& moveit::tools::Profiler::Instance(void)
00040 {
00041   static Profiler p(false, false);
00042   return p;
00043 }
00044 
00045 #if MOVEIT_ENABLE_PROFILING
00046 
00047 #include <console_bridge/console.h>
00048 #include <vector>
00049 #include <algorithm>
00050 #include <sstream>
00051 
00052 void moveit::tools::Profiler::start(void)
00053 {
00054   lock_.lock();
00055   if (!running_)
00056   {
00057     tinfo_.set();
00058     running_ = true;
00059   }
00060   lock_.unlock();
00061 }
00062 
00063 void moveit::tools::Profiler::stop(void)
00064 {
00065   lock_.lock();
00066   if (running_)
00067   {
00068     tinfo_.update();
00069     running_ = false;
00070   }
00071   lock_.unlock();
00072 }
00073 
00074 void moveit::tools::Profiler::clear(void)
00075 {
00076   lock_.lock();
00077   data_.clear();
00078   tinfo_ = TimeInfo();
00079   if (running_)
00080     tinfo_.set();
00081   lock_.unlock();
00082 }
00083 
00084 void moveit::tools::Profiler::event(const std::string& name, const unsigned int times)
00085 {
00086   lock_.lock();
00087   data_[boost::this_thread::get_id()].events[name] += times;
00088   lock_.unlock();
00089 }
00090 
00091 void moveit::tools::Profiler::average(const std::string& name, const double value)
00092 {
00093   lock_.lock();
00094   AvgInfo& a = data_[boost::this_thread::get_id()].avg[name];
00095   a.total += value;
00096   a.totalSqr += value * value;
00097   a.parts++;
00098   lock_.unlock();
00099 }
00100 
00101 void moveit::tools::Profiler::begin(const std::string& name)
00102 {
00103   lock_.lock();
00104   data_[boost::this_thread::get_id()].time[name].set();
00105   lock_.unlock();
00106 }
00107 
00108 void moveit::tools::Profiler::end(const std::string& name)
00109 {
00110   lock_.lock();
00111   data_[boost::this_thread::get_id()].time[name].update();
00112   lock_.unlock();
00113 }
00114 
00115 namespace
00116 {
00117 inline double to_seconds(const boost::posix_time::time_duration& d)
00118 {
00119   return (double)d.total_microseconds() / 1000000.0;
00120 }
00121 }
00122 
00123 void moveit::tools::Profiler::status(std::ostream& out, bool merge)
00124 {
00125   stop();
00126   lock_.lock();
00127   printOnDestroy_ = false;
00128 
00129   out << std::endl;
00130   out << " *** Profiling statistics. Total counted time : " << to_seconds(tinfo_.total) << " seconds" << std::endl;
00131 
00132   if (merge)
00133   {
00134     PerThread combined;
00135     for (std::map<boost::thread::id, PerThread>::const_iterator it = data_.begin(); it != data_.end(); ++it)
00136     {
00137       for (std::map<std::string, unsigned long int>::const_iterator iev = it->second.events.begin();
00138            iev != it->second.events.end(); ++iev)
00139         combined.events[iev->first] += iev->second;
00140       for (std::map<std::string, AvgInfo>::const_iterator iavg = it->second.avg.begin(); iavg != it->second.avg.end();
00141            ++iavg)
00142       {
00143         combined.avg[iavg->first].total += iavg->second.total;
00144         combined.avg[iavg->first].totalSqr += iavg->second.totalSqr;
00145         combined.avg[iavg->first].parts += iavg->second.parts;
00146       }
00147       for (std::map<std::string, TimeInfo>::const_iterator itm = it->second.time.begin(); itm != it->second.time.end();
00148            ++itm)
00149       {
00150         TimeInfo& tc = combined.time[itm->first];
00151         tc.total = tc.total + itm->second.total;
00152         tc.parts = tc.parts + itm->second.parts;
00153         if (tc.shortest > itm->second.shortest)
00154           tc.shortest = itm->second.shortest;
00155         if (tc.longest < itm->second.longest)
00156           tc.longest = itm->second.longest;
00157       }
00158     }
00159     printThreadInfo(out, combined);
00160   }
00161   else
00162     for (std::map<boost::thread::id, PerThread>::const_iterator it = data_.begin(); it != data_.end(); ++it)
00163     {
00164       out << "Thread " << it->first << ":" << std::endl;
00165       printThreadInfo(out, it->second);
00166     }
00167   lock_.unlock();
00168 }
00169 
00170 void moveit::tools::Profiler::console(void)
00171 {
00172   std::stringstream ss;
00173   ss << std::endl;
00174   status(ss, true);
00175   logInform(ss.str().c_str());
00176 }
00177 
00179 namespace
00180 {
00181 struct dataIntVal
00182 {
00183   std::string name;
00184   unsigned long int value;
00185 };
00186 
00187 struct SortIntByValue
00188 {
00189   bool operator()(const dataIntVal& a, const dataIntVal& b) const
00190   {
00191     return a.value > b.value;
00192   }
00193 };
00194 
00195 struct dataDoubleVal
00196 {
00197   std::string name;
00198   double value;
00199 };
00200 
00201 struct SortDoubleByValue
00202 {
00203   bool operator()(const dataDoubleVal& a, const dataDoubleVal& b) const
00204   {
00205     return a.value > b.value;
00206   }
00207 };
00208 }
00210 
00211 void moveit::tools::Profiler::printThreadInfo(std::ostream& out, const PerThread& data)
00212 {
00213   double total = to_seconds(tinfo_.total);
00214 
00215   std::vector<dataIntVal> events;
00216   for (std::map<std::string, unsigned long int>::const_iterator iev = data.events.begin(); iev != data.events.end();
00217        ++iev)
00218   {
00219     dataIntVal next = { iev->first, iev->second };
00220     events.push_back(next);
00221   }
00222   std::sort(events.begin(), events.end(), SortIntByValue());
00223   if (!events.empty())
00224     out << "Events:" << std::endl;
00225   for (unsigned int i = 0; i < events.size(); ++i)
00226     out << events[i].name << ": " << events[i].value << std::endl;
00227 
00228   std::vector<dataDoubleVal> avg;
00229   for (std::map<std::string, AvgInfo>::const_iterator ia = data.avg.begin(); ia != data.avg.end(); ++ia)
00230   {
00231     dataDoubleVal next = { ia->first, ia->second.total / (double)ia->second.parts };
00232     avg.push_back(next);
00233   }
00234   std::sort(avg.begin(), avg.end(), SortDoubleByValue());
00235   if (!avg.empty())
00236     out << "Averages:" << std::endl;
00237   for (unsigned int i = 0; i < avg.size(); ++i)
00238   {
00239     const AvgInfo& a = data.avg.find(avg[i].name)->second;
00240     out << avg[i].name << ": " << avg[i].value << " (stddev = "
00241         << sqrt(fabs(a.totalSqr - (double)a.parts * avg[i].value * avg[i].value) / ((double)a.parts - 1.)) << ")"
00242         << std::endl;
00243   }
00244 
00245   std::vector<dataDoubleVal> time;
00246 
00247   for (std::map<std::string, TimeInfo>::const_iterator itm = data.time.begin(); itm != data.time.end(); ++itm)
00248   {
00249     dataDoubleVal next = { itm->first, to_seconds(itm->second.total) };
00250     time.push_back(next);
00251   }
00252 
00253   std::sort(time.begin(), time.end(), SortDoubleByValue());
00254   if (!time.empty())
00255     out << "Blocks of time:" << std::endl;
00256 
00257   double unaccounted = total;
00258   for (unsigned int i = 0; i < time.size(); ++i)
00259   {
00260     const TimeInfo& d = data.time.find(time[i].name)->second;
00261 
00262     double tS = to_seconds(d.shortest);
00263     double tL = to_seconds(d.longest);
00264     out << time[i].name << ": " << time[i].value << "s (" << (100.0 * time[i].value / total) << "%), [" << tS
00265         << "s --> " << tL << " s], " << d.parts << " parts";
00266     if (d.parts > 0)
00267     {
00268       double pavg = to_seconds(d.total) / (double)d.parts;
00269       out << ", " << pavg << " s on average";
00270       if (pavg < 1.0)
00271         out << " (" << 1.0 / pavg << " /s)";
00272     }
00273     out << std::endl;
00274     unaccounted -= time[i].value;
00275   }
00276   // if we do not appear to have counted time multiple times, print the unaccounted time too
00277   if (unaccounted >= 0.0)
00278   {
00279     out << "Unaccounted time : " << unaccounted;
00280     if (total > 0.0)
00281       out << " (" << (100.0 * unaccounted / total) << " %)";
00282     out << std::endl;
00283   }
00284 
00285   out << std::endl;
00286 }
00287 
00288 #endif


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:49