TimingTools.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, LABUST, UNIZG-FER
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 LABUST 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 #ifndef TIMINGTOOLS_HPP_
00035 #define TIMINGTOOLS_HPP_
00036 #include <boost/date_time/posix_time/posix_time.hpp>
00037 #include <boost/thread/thread.hpp>
00038 #include <boost/function.hpp>
00039 #include <boost/noncopyable.hpp>
00040 
00041 namespace labust
00042 {
00043   namespace tools
00044   {
00050     inline double unix_time()
00051     {
00052       using namespace boost::posix_time;
00053       using namespace boost::gregorian;
00054       ptime epoch(date(1970,1,1));
00055       ptime t(microsec_clock::local_time());
00056       return (t-epoch).total_microseconds()/1000000.;
00057     }
00064     inline std::string time_signature()
00065     {
00066       using namespace boost::posix_time;
00067       using namespace boost::gregorian;
00068       std::stringstream out;
00069       ptime t(second_clock::local_time());
00070       out<<t.date().year();
00071       out<<"_"<<t.date().month();
00072       out<<"_"<<t.date().day();
00073       out<<"_"<<t.time_of_day().hours();
00074       out<<"_"<<t.time_of_day().minutes();
00075       out<<"_"<<t.time_of_day().seconds();
00076 
00077       return out.str();
00078     }
00085     inline std::string unix_time_string(bool microseconds = false)
00086     {
00087       std::stringstream out;
00088       out.precision(6);
00089       out<<std::fixed<<(microseconds ? unix_time() : long(unix_time()));
00090       return out.str();
00091     }
00097     inline void sleep(size_t ms)
00098     {
00099         boost::this_thread::sleep(boost::posix_time::milliseconds(ms));
00100     };
00106     struct wait_until_ms
00107     {
00113       wait_until_ms(size_t ms):
00114 #ifdef unix
00115         time(ms*1000){};
00116 #else
00117         time(ms){};
00118 #endif
00119 
00123       inline void operator() ()
00124       {
00125         using namespace boost;
00126         using namespace posix_time;
00127 #ifdef unix
00128         this_thread::sleep(microseconds(time - microsec_clock::local_time().time_of_day().total_microseconds()%time));
00129 #else
00130         this_thread::sleep(milliseconds(time - microsec_clock::local_time().time_of_day().total_milliseconds()%time));
00131 #endif
00132       }
00133         private:
00137       size_t time;
00138     };
00143     struct watchdog : boost::noncopyable
00144     {
00152       watchdog(const boost::function<void (void)>& func, size_t timeout_ms = 500, size_t loop_ms = 100):
00153         func(func),
00154         counter(0),
00155         timeout_ms(timeout_ms),
00156         loop_ms(loop_ms),
00157         runner(boost::bind(&watchdog::run,this)){};
00161       ~watchdog()
00162       {
00163         runner.interrupt();
00164         runner.join();
00165       }
00166 
00170       void reset(){boost::mutex::scoped_lock lock(cntMutex); this->counter = 0;};
00171 
00172     private:
00176       void run()
00177       try
00178       {
00179         while (true)
00180         {
00181                 using namespace boost;
00182                 using namespace posix_time;
00183                 sleep(loop_ms);
00184                 boost::mutex::scoped_lock lock(cntMutex);
00185                 counter += loop_ms;
00186                 if (counter >= timeout_ms) func();
00187         }
00188       }
00189       catch (boost::thread_interrupted&){};
00190 
00194       boost::function<void (void)> func;
00198       volatile size_t counter;
00202       size_t timeout_ms, loop_ms;
00206       boost::thread runner;
00210       boost::mutex cntMutex;
00211     };
00212   }
00213 }
00214 /* TIMINGTOOLS_HPP_ */
00215 #endif


snippets
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:33