00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef ROS_TIME_H
00036 #define ROS_TIME_H
00037
00038
00039
00040
00041
00042 #include <iostream>
00043 #include <cmath>
00044 #include <ros/exception.h>
00045 #include "duration.h"
00046
00047
00048
00049
00050
00051 #ifdef WIN32
00052 #include <windows.h>
00053 #include <sys/timeb.h>
00054 #else
00055 #include <sys/time.h>
00056 #endif
00057
00058 namespace ros
00059 {
00060
00061
00062
00063
00064
00068 class TimeNotInitializedException : public Exception
00069 {
00070 public:
00071 TimeNotInitializedException()
00072 : Exception("Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. "
00073 "If this is a standalone app or test that just uses ros::Time and does not communicate over ROS, you may also call ros::Time::init()")
00074 {}
00075 };
00076
00082 class NoHighPerformanceTimersException : public Exception
00083 {
00084 public:
00085 NoHighPerformanceTimersException()
00086 : Exception("This windows platform does not "
00087 "support the high-performance timing api.")
00088 {}
00089 };
00090
00091
00092
00093
00094
00095 inline void normalizeSecNSec(uint64_t& sec, uint64_t& nsec)
00096 {
00097 uint64_t nsec_part = nsec % 1000000000UL;
00098 uint64_t sec_part = nsec / 1000000000UL;
00099
00100 if (sec_part > UINT_MAX)
00101 throw std::runtime_error("Time is out of dual 32-bit range");
00102
00103 sec += sec_part;
00104 nsec = nsec_part;
00105 }
00106
00107 inline void normalizeSecNSec(uint32_t& sec, uint32_t& nsec)
00108 {
00109 uint64_t sec64 = sec;
00110 uint64_t nsec64 = nsec;
00111
00112 normalizeSecNSec(sec64, nsec64);
00113
00114 sec = (uint32_t)sec64;
00115 nsec = (uint32_t)nsec64;
00116 }
00117
00118 inline void normalizeSecNSecUnsigned(int64_t& sec, int64_t& nsec)
00119 {
00120 int64_t nsec_part = nsec;
00121 int64_t sec_part = sec;
00122
00123 while (nsec_part >= 1000000000L)
00124 {
00125 nsec_part -= 1000000000L;
00126 ++sec_part;
00127 }
00128 while (nsec_part < 0)
00129 {
00130 nsec_part += 1000000000L;
00131 --sec_part;
00132 }
00133
00134 if (sec_part < 0 || sec_part > INT_MAX)
00135 throw std::runtime_error("Time is out of dual 32-bit range");
00136
00137 sec = sec_part;
00138 nsec = nsec_part;
00139 }
00140
00141
00142
00143
00144
00149 template<class T, class D>
00150 class TimeBase
00151 {
00152 public:
00153 uint32_t sec, nsec;
00154
00155 TimeBase() : sec(0), nsec(0) { }
00156 TimeBase(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec)
00157 {
00158 normalizeSecNSec(sec, nsec);
00159 }
00160 explicit TimeBase(double t) { fromSec(t); }
00161 ~TimeBase() {}
00162 D operator-(const T &rhs) const;
00163 T operator+(const D &rhs) const;
00164 T operator-(const D &rhs) const;
00165 T& operator+=(const D &rhs);
00166 T& operator-=(const D &rhs);
00167 bool operator==(const T &rhs) const;
00168 inline bool operator!=(const T &rhs) const { return !(*static_cast<const T*>(this) == rhs); }
00169 bool operator>(const T &rhs) const;
00170 bool operator<(const T &rhs) const;
00171 bool operator>=(const T &rhs) const;
00172 bool operator<=(const T &rhs) const;
00173
00174 double toSec() const { return (double)sec + 1e-9*(double)nsec; };
00175 T& fromSec(double t) { sec = (uint32_t)floor(t); nsec = (uint32_t)round((t-sec) * 1e9); return *static_cast<T*>(this);}
00176
00177 uint64_t toNSec() const {return (uint64_t)sec*1000000000ull + (uint64_t)nsec; }
00178 T& fromNSec(uint64_t t);
00179
00180 inline bool isZero() const { return sec == 0 && nsec == 0; }
00181 inline bool is_zero() const { return isZero(); }
00182 };
00183
00189 class Time : public TimeBase<Time, Duration>
00190 {
00191 public:
00192 Time()
00193 : TimeBase<Time, Duration>()
00194 {}
00195
00196 Time(uint32_t _sec, uint32_t _nsec)
00197 : TimeBase<Time, Duration>(_sec, _nsec)
00198 {}
00199
00200 explicit Time(double t) { fromSec(t); }
00201
00206 static Time now();
00210 static bool sleepUntil(const Time& end);
00211
00212 static void init();
00213 static void shutdown();
00214 static void setNow(const Time& new_now);
00215 static bool useSystemTime();
00216 static bool isSimTime();
00217 static bool isSystemTime();
00218
00222 static bool isValid();
00226 static bool waitForValid();
00230 static bool waitForValid(const ros::WallDuration& timeout);
00231 };
00232
00233 extern const Time TIME_MAX;
00234 extern const Time TIME_MIN;
00235
00241 class WallTime : public TimeBase<WallTime, WallDuration>
00242 {
00243 public:
00244 WallTime()
00245 : TimeBase<WallTime, WallDuration>()
00246 {}
00247
00248 WallTime(uint32_t _sec, uint32_t _nsec)
00249 : TimeBase<WallTime, WallDuration>(_sec, _nsec)
00250 {}
00251
00252 explicit WallTime(double t) { fromSec(t); }
00253
00257 static WallTime now();
00258
00262 static bool sleepUntil(const WallTime& end);
00263
00264 static bool isSystemTime() { return true; }
00265 };
00266
00267 std::ostream &operator <<(std::ostream &os, const Time &rhs);
00268 std::ostream &operator <<(std::ostream &os, const WallTime &rhs);
00269
00270 template<class T, class D>
00271 T& TimeBase<T, D>::fromNSec(uint64_t t)
00272 {
00273 sec = (int32_t)(t / 1000000000);
00274 nsec = (int32_t)(t % 1000000000);
00275
00276 normalizeSecNSec(sec, nsec);
00277
00278 return *static_cast<T*>(this);
00279 }
00280
00281 template<class T, class D>
00282 D TimeBase<T, D>::operator-(const T &rhs) const
00283 {
00284 return D((int32_t)sec - (int32_t)rhs.sec,
00285 (int32_t)nsec - (int32_t)rhs.nsec);
00286 }
00287
00288 template<class T, class D>
00289 T TimeBase<T, D>::operator-(const D &rhs) const
00290 {
00291 return *static_cast<const T*>(this) + ( -rhs);
00292 }
00293
00294 template<class T, class D>
00295 T TimeBase<T, D>::operator+(const D &rhs) const
00296 {
00297 int64_t sec_sum = (int64_t)sec + (int64_t)rhs.sec;
00298 int64_t nsec_sum = (int64_t)nsec + (int64_t)rhs.nsec;
00299
00300
00301 normalizeSecNSecUnsigned(sec_sum, nsec_sum);
00302
00303
00304 return T((uint32_t)sec_sum, (uint32_t)nsec_sum);
00305 }
00306
00307 template<class T, class D>
00308 T& TimeBase<T, D>::operator+=(const D &rhs)
00309 {
00310 *this = *this + rhs;
00311 return *static_cast<T*>(this);
00312 }
00313
00314 template<class T, class D>
00315 T& TimeBase<T, D>::operator-=(const D &rhs)
00316 {
00317 *this += (-rhs);
00318 return *static_cast<T*>(this);
00319 }
00320
00321 template<class T, class D>
00322 bool TimeBase<T, D>::operator==(const T &rhs) const
00323 {
00324 return sec == rhs.sec && nsec == rhs.nsec;
00325 }
00326
00327 template<class T, class D>
00328 bool TimeBase<T, D>::operator<(const T &rhs) const
00329 {
00330 if (sec < rhs.sec)
00331 return true;
00332 else if (sec == rhs.sec && nsec < rhs.nsec)
00333 return true;
00334 return false;
00335 }
00336
00337 template<class T, class D>
00338 bool TimeBase<T, D>::operator>(const T &rhs) const
00339 {
00340 if (sec > rhs.sec)
00341 return true;
00342 else if (sec == rhs.sec && nsec > rhs.nsec)
00343 return true;
00344 return false;
00345 }
00346
00347 template<class T, class D>
00348 bool TimeBase<T, D>::operator<=(const T &rhs) const
00349 {
00350 if (sec < rhs.sec)
00351 return true;
00352 else if (sec == rhs.sec && nsec <= rhs.nsec)
00353 return true;
00354 return false;
00355 }
00356
00357 template<class T, class D>
00358 bool TimeBase<T, D>::operator>=(const T &rhs) const
00359 {
00360 if (sec > rhs.sec)
00361 return true;
00362 else if (sec == rhs.sec && nsec >= rhs.nsec)
00363 return true;
00364 return false;
00365 }
00366
00367 }
00368
00369 #endif // ROS_TIME_H
00370