$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, 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, Inc. 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 #ifdef _MSC_VER 00035 #ifndef NOMINMAX 00036 #define NOMINMAX 00037 #endif 00038 #endif 00039 00040 #include "ros/time.h" 00041 #include "ros/impl/time.h" 00042 #include <cmath> 00043 #include <ctime> 00044 #include <iomanip> 00045 #include <stdexcept> 00046 #include <limits> 00047 00048 #include <boost/thread/mutex.hpp> 00049 #include <boost/io/ios_state.hpp> 00050 00051 /********************************************************************* 00052 ** Preprocessor 00053 *********************************************************************/ 00054 00055 // Could probably do some better and more elaborate checking 00056 // and definition here. 00057 #define HAS_CLOCK_GETTIME (_POSIX_C_SOURCE >= 199309L) 00058 00059 /********************************************************************* 00060 ** Namespaces 00061 *********************************************************************/ 00062 00063 namespace ros 00064 { 00065 00066 /********************************************************************* 00067 ** Variables 00068 *********************************************************************/ 00069 00070 const Duration DURATION_MAX(std::numeric_limits<int32_t>::max(), 999999999); 00071 const Duration DURATION_MIN(std::numeric_limits<int32_t>::min(), 0); 00072 00073 const Time TIME_MAX(std::numeric_limits<uint32_t>::max(), 999999999); 00074 const Time TIME_MIN(0, 1); 00075 00076 // This is declared here because it's set from the Time class but read from 00077 // the Duration class, and need not be exported to users of either. 00078 static bool g_stopped(false); 00079 00080 // I assume that this is declared here, instead of time.h, to keep users 00081 // of time.h from including boost/thread/mutex.hpp 00082 static boost::mutex g_sim_time_mutex; 00083 00084 static bool g_initialized(false); 00085 static bool g_use_sim_time(true); 00086 static Time g_sim_time(0, 0); 00087 00088 /********************************************************************* 00089 ** Cross Platform Functions 00090 *********************************************************************/ 00091 /* 00092 * These have only internal linkage to this translation unit. 00093 * (i.e. not exposed to users of the time classes) 00094 */ 00095 void ros_walltime(uint32_t& sec, uint32_t& nsec) 00096 #ifndef WIN32 00097 throw(NoHighPerformanceTimersException) 00098 #endif 00099 { 00100 #ifndef WIN32 00101 #if HAS_CLOCK_GETTIME 00102 timespec start; 00103 clock_gettime(CLOCK_REALTIME, &start); 00104 sec = start.tv_sec; 00105 nsec = start.tv_nsec; 00106 #else 00107 struct timeval timeofday; 00108 gettimeofday(&timeofday,NULL); 00109 sec = timeofday.tv_sec; 00110 nsec = timeofday.tv_usec * 1000; 00111 #endif 00112 #else 00113 // Win32 implementation 00114 // unless I've missed something obvious, the only way to get high-precision 00115 // time on Windows is via the QueryPerformanceCounter() call. However, 00116 // this is somewhat problematic in Windows XP on some processors, especially 00117 // AMD, because the Windows implementation can freak out when the CPU clocks 00118 // down to save power. Time can jump or even go backwards. Microsoft has 00119 // fixed this bug for most systems now, but it can still show up if you have 00120 // not installed the latest CPU drivers (an oxymoron). They fixed all these 00121 // problems in Windows Vista, and this API is by far the most accurate that 00122 // I know of in Windows, so I'll use it here despite all these caveats 00123 static LARGE_INTEGER cpu_freq, init_cpu_time; 00124 uint32_t start_sec = 0; 00125 uint32_t start_nsec = 0; 00126 if ( ( start_sec == 0 ) && ( start_nsec == 0 ) ) 00127 { 00128 QueryPerformanceFrequency(&cpu_freq); 00129 if (cpu_freq.QuadPart == 0) { 00130 throw NoHighPerformanceTimersException(); 00131 } 00132 QueryPerformanceCounter(&init_cpu_time); 00133 // compute an offset from the Epoch using the lower-performance timer API 00134 FILETIME ft; 00135 GetSystemTimeAsFileTime(&ft); 00136 LARGE_INTEGER start_li; 00137 start_li.LowPart = ft.dwLowDateTime; 00138 start_li.HighPart = ft.dwHighDateTime; 00139 // why did they choose 1601 as the time zero, instead of 1970? 00140 // there were no outstanding hard rock bands in 1601. 00141 #ifdef _MSC_VER 00142 start_li.QuadPart -= 116444736000000000Ui64; 00143 #else 00144 start_li.QuadPart -= 116444736000000000ULL; 00145 #endif 00146 start_sec = (uint32_t)(start_li.QuadPart / 10000000); // 100-ns units. odd. 00147 start_nsec = (start_li.LowPart % 10000000) * 100; 00148 } 00149 LARGE_INTEGER cur_time; 00150 QueryPerformanceCounter(&cur_time); 00151 LARGE_INTEGER delta_cpu_time; 00152 delta_cpu_time.QuadPart = cur_time.QuadPart - init_cpu_time.QuadPart; 00153 // todo: how to handle cpu clock drift. not sure it's a big deal for us. 00154 // also, think about clock wraparound. seems extremely unlikey, but possible 00155 double d_delta_cpu_time = delta_cpu_time.QuadPart / (double) cpu_freq.QuadPart; 00156 uint32_t delta_sec = (uint32_t) floor(d_delta_cpu_time); 00157 uint32_t delta_nsec = (uint32_t) boost::math::round((d_delta_cpu_time-delta_sec) * 1e9); 00158 00159 int64_t sec_sum = (int64_t)start_sec + (int64_t)delta_sec; 00160 int64_t nsec_sum = (int64_t)start_nsec + (int64_t)delta_nsec; 00161 00162 // Throws an exception if we go out of 32-bit range 00163 normalizeSecNSecUnsigned(sec_sum, nsec_sum); 00164 00165 sec = sec_sum; 00166 nsec = nsec_sum; 00167 #endif 00168 } 00172 int ros_nanosleep(const uint32_t &sec, const uint32_t &nsec) 00173 { 00174 #if defined(WIN32) 00175 HANDLE timer = NULL; 00176 LARGE_INTEGER sleepTime; 00177 sleepTime.QuadPart = - 00178 static_cast<int64_t>(sec)*10000000LL - 00179 static_cast<int64_t>(nsec) / 100LL; 00180 00181 timer = CreateWaitableTimer(NULL, TRUE, NULL); 00182 if (timer == NULL) 00183 { 00184 return -1; 00185 } 00186 00187 if (!SetWaitableTimer (timer, &sleepTime, 0, NULL, NULL, 0)) 00188 { 00189 return -1; 00190 } 00191 00192 if (WaitForSingleObject (timer, INFINITE) != WAIT_OBJECT_0) 00193 { 00194 return -1; 00195 } 00196 return 0; 00197 #else 00198 timespec req = { sec, nsec }; 00199 return nanosleep(&req, NULL); 00200 #endif 00201 } 00202 00208 bool ros_wallsleep(uint32_t sec, uint32_t nsec) 00209 { 00210 #if defined(WIN32) 00211 ros_nanosleep(sec,nsec); 00212 #else 00213 timespec req = { sec, nsec }; 00214 timespec rem = {0, 0}; 00215 while (nanosleep(&req, &rem) && !g_stopped) 00216 { 00217 req = rem; 00218 } 00219 #endif 00220 return !g_stopped; 00221 } 00222 00223 /********************************************************************* 00224 ** Class Methods 00225 *********************************************************************/ 00226 00227 bool Time::useSystemTime() 00228 { 00229 return !g_use_sim_time; 00230 } 00231 00232 bool Time::isSimTime() 00233 { 00234 return g_use_sim_time; 00235 } 00236 00237 bool Time::isSystemTime() 00238 { 00239 return !isSimTime(); 00240 } 00241 00242 Time Time::now() 00243 { 00244 if (!g_initialized) 00245 { 00246 throw TimeNotInitializedException(); 00247 } 00248 00249 if (g_use_sim_time) 00250 { 00251 boost::mutex::scoped_lock lock(g_sim_time_mutex); 00252 Time t = g_sim_time; 00253 return t; 00254 } 00255 00256 Time t; 00257 ros_walltime(t.sec, t.nsec); 00258 00259 return t; 00260 } 00261 00262 void Time::setNow(const Time& new_now) 00263 { 00264 boost::mutex::scoped_lock lock(g_sim_time_mutex); 00265 00266 g_sim_time = new_now; 00267 g_use_sim_time = true; 00268 } 00269 00270 void Time::init() 00271 { 00272 g_stopped = false; 00273 g_use_sim_time = false; 00274 g_initialized = true; 00275 } 00276 00277 void Time::shutdown() 00278 { 00279 g_stopped = true; 00280 } 00281 00282 bool Time::isValid() 00283 { 00284 return (!g_use_sim_time) || !g_sim_time.isZero(); 00285 } 00286 00287 bool Time::waitForValid() 00288 { 00289 return waitForValid(ros::WallDuration()); 00290 } 00291 00292 bool Time::waitForValid(const ros::WallDuration& timeout) 00293 { 00294 ros::WallTime start = ros::WallTime::now(); 00295 while (!isValid() && !g_stopped) 00296 { 00297 ros::WallDuration(0.01).sleep(); 00298 00299 if (timeout > ros::WallDuration(0, 0) && (ros::WallTime::now() - start > timeout)) 00300 { 00301 return false; 00302 } 00303 } 00304 00305 if (g_stopped) 00306 { 00307 return false; 00308 } 00309 00310 return true; 00311 } 00312 00313 std::ostream& operator<<(std::ostream& os, const Time &rhs) 00314 { 00315 boost::io::ios_all_saver s(os); 00316 os << rhs.sec << "." << std::setw(9) << std::setfill('0') << rhs.nsec; 00317 return os; 00318 } 00319 00320 std::ostream& operator<<(std::ostream& os, const Duration& rhs) 00321 { 00322 boost::io::ios_all_saver s(os); 00323 os << rhs.sec << "." << std::setw(9) << std::setfill('0') << rhs.nsec; 00324 return os; 00325 } 00326 00327 bool Time::sleepUntil(const Time& end) 00328 { 00329 if (Time::useSystemTime()) 00330 { 00331 Duration d(end - Time::now()); 00332 if (d > Duration(0)) 00333 { 00334 return d.sleep(); 00335 } 00336 00337 return true; 00338 } 00339 else 00340 { 00341 Time start = Time::now(); 00342 while (!g_stopped && (Time::now() < end)) 00343 { 00344 ros_nanosleep(0,1000000); 00345 if (Time::now() < start) 00346 { 00347 return false; 00348 } 00349 } 00350 00351 return true; 00352 } 00353 } 00354 00355 bool WallTime::sleepUntil(const WallTime& end) 00356 { 00357 WallDuration d(end - WallTime::now()); 00358 if (d > WallDuration(0)) 00359 { 00360 return d.sleep(); 00361 } 00362 00363 return true; 00364 } 00365 00366 bool Duration::sleep() const 00367 { 00368 if (Time::useSystemTime()) 00369 { 00370 return ros_wallsleep(sec, nsec); 00371 } 00372 else 00373 { 00374 Time start = Time::now(); 00375 Time end = start + *this; 00376 if (start.isZero()) 00377 { 00378 end = TIME_MAX; 00379 } 00380 00381 while (!g_stopped && (Time::now() < end)) 00382 { 00383 ros_wallsleep(0, 1000000); 00384 00385 // If we started at time 0 wait for the first actual time to arrive before starting the timer on 00386 // our sleep 00387 if (start.isZero()) 00388 { 00389 start = Time::now(); 00390 end = start + *this; 00391 } 00392 00393 // If time jumped backwards from when we started sleeping, return immediately 00394 if (Time::now() < start) 00395 { 00396 return false; 00397 } 00398 } 00399 00400 return true; 00401 } 00402 } 00403 00404 std::ostream &operator<<(std::ostream& os, const WallTime &rhs) 00405 { 00406 boost::io::ios_all_saver s(os); 00407 os << rhs.sec << "." << std::setw(9) << std::setfill('0') << rhs.nsec; 00408 return os; 00409 } 00410 00411 WallTime WallTime::now() 00412 { 00413 WallTime t; 00414 ros_walltime(t.sec, t.nsec); 00415 00416 return t; 00417 } 00418 00419 std::ostream &operator<<(std::ostream& os, const WallDuration& rhs) 00420 { 00421 boost::io::ios_all_saver s(os); 00422 os << rhs.sec << "." << std::setw(9) << std::setfill('0') << rhs.nsec; 00423 return os; 00424 } 00425 00426 bool WallDuration::sleep() const 00427 { 00428 return ros_wallsleep(sec, nsec); 00429 } 00430 00431 void normalizeSecNSec(uint64_t& sec, uint64_t& nsec) 00432 { 00433 uint64_t nsec_part = nsec % 1000000000UL; 00434 uint64_t sec_part = nsec / 1000000000UL; 00435 00436 if (sec_part > UINT_MAX) 00437 throw std::runtime_error("Time is out of dual 32-bit range"); 00438 00439 sec += sec_part; 00440 nsec = nsec_part; 00441 } 00442 00443 void normalizeSecNSec(uint32_t& sec, uint32_t& nsec) 00444 { 00445 uint64_t sec64 = sec; 00446 uint64_t nsec64 = nsec; 00447 00448 normalizeSecNSec(sec64, nsec64); 00449 00450 sec = (uint32_t)sec64; 00451 nsec = (uint32_t)nsec64; 00452 } 00453 00454 void normalizeSecNSecUnsigned(int64_t& sec, int64_t& nsec) 00455 { 00456 int64_t nsec_part = nsec; 00457 int64_t sec_part = sec; 00458 00459 while (nsec_part >= 1000000000L) 00460 { 00461 nsec_part -= 1000000000L; 00462 ++sec_part; 00463 } 00464 while (nsec_part < 0) 00465 { 00466 nsec_part += 1000000000L; 00467 --sec_part; 00468 } 00469 00470 if (sec_part < 0 || sec_part > INT_MAX) 00471 throw std::runtime_error("Time is out of dual 32-bit range"); 00472 00473 sec = sec_part; 00474 nsec = nsec_part; 00475 } 00476 00477 template class TimeBase<Time, Duration>; 00478 template class TimeBase<WallTime, WallDuration>; 00479 } 00480 00481