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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:47