Go to the documentation of this file.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_INCLUDED
00036 #define ROS_TIME_H_INCLUDED
00037
00038
00039
00040
00041
00042 #ifdef _MSC_VER
00043
00044
00045 #pragma warning(disable: 4244)
00046 #pragma warning(disable: 4661)
00047 #endif
00048
00049
00050
00051
00052
00053 #include <ros/platform.h>
00054 #include <iostream>
00055 #include <cmath>
00056 #include <ros/exception.h>
00057 #include "duration.h"
00058 #include <boost/math/special_functions/round.hpp>
00059 #include "rostime_decl.h"
00060
00061
00062
00063
00064
00065 #ifdef WIN32
00066 #include <sys/timeb.h>
00067 #else
00068 #include <sys/time.h>
00069 #endif
00070
00071 namespace boost {
00072 namespace posix_time {
00073 class ptime;
00074 class time_duration;
00075 }
00076 }
00077
00078 namespace ros
00079 {
00080
00081
00082
00083
00084
00088 class ROSTIME_DECL TimeNotInitializedException : public Exception
00089 {
00090 public:
00091 TimeNotInitializedException()
00092 : Exception("Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. "
00093 "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()")
00094 {}
00095 };
00096
00102 class ROSTIME_DECL NoHighPerformanceTimersException : public Exception
00103 {
00104 public:
00105 NoHighPerformanceTimersException()
00106 : Exception("This windows platform does not "
00107 "support the high-performance timing api.")
00108 {}
00109 };
00110
00111
00112
00113
00114
00115 ROSTIME_DECL void normalizeSecNSec(uint64_t& sec, uint64_t& nsec);
00116 ROSTIME_DECL void normalizeSecNSec(uint32_t& sec, uint32_t& nsec);
00117 ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t& sec, int64_t& nsec);
00118
00119
00120
00121
00122
00127 template<class T, class D>
00128 class TimeBase
00129 {
00130 public:
00131 uint32_t sec, nsec;
00132
00133 TimeBase() : sec(0), nsec(0) { }
00134 TimeBase(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec)
00135 {
00136 normalizeSecNSec(sec, nsec);
00137 }
00138 explicit TimeBase(double t) { fromSec(t); }
00139 ~TimeBase() {}
00140 D operator-(const T &rhs) const;
00141 T operator+(const D &rhs) const;
00142 T operator-(const D &rhs) const;
00143 T& operator+=(const D &rhs);
00144 T& operator-=(const D &rhs);
00145 bool operator==(const T &rhs) const;
00146 inline bool operator!=(const T &rhs) const { return !(*static_cast<const T*>(this) == rhs); }
00147 bool operator>(const T &rhs) const;
00148 bool operator<(const T &rhs) const;
00149 bool operator>=(const T &rhs) const;
00150 bool operator<=(const T &rhs) const;
00151
00152 double toSec() const { return (double)sec + 1e-9*(double)nsec; };
00153 T& fromSec(double t) {
00154 sec = (uint32_t)floor(t);
00155 nsec = (uint32_t)boost::math::round((t-sec) * 1e9);
00156
00157 sec += (nsec / 1000000000ul);
00158 nsec %= 1000000000ul;
00159 return *static_cast<T*>(this);
00160 }
00161
00162 uint64_t toNSec() const {return (uint64_t)sec*1000000000ull + (uint64_t)nsec; }
00163 T& fromNSec(uint64_t t);
00164
00165 inline bool isZero() const { return sec == 0 && nsec == 0; }
00166 inline bool is_zero() const { return isZero(); }
00167 boost::posix_time::ptime toBoost() const;
00168
00169 };
00170
00176 class ROSTIME_DECL Time : public TimeBase<Time, Duration>
00177 {
00178 public:
00179 Time()
00180 : TimeBase<Time, Duration>()
00181 {}
00182
00183 Time(uint32_t _sec, uint32_t _nsec)
00184 : TimeBase<Time, Duration>(_sec, _nsec)
00185 {}
00186
00187 explicit Time(double t) { fromSec(t); }
00188
00193 static Time now();
00197 static bool sleepUntil(const Time& end);
00198
00199 static void init();
00200 static void shutdown();
00201 static void setNow(const Time& new_now);
00202 static bool useSystemTime();
00203 static bool isSimTime();
00204 static bool isSystemTime();
00205
00209 static bool isValid();
00213 static bool waitForValid();
00217 static bool waitForValid(const ros::WallDuration& timeout);
00218
00219 static Time fromBoost(const boost::posix_time::ptime& t);
00220 static Time fromBoost(const boost::posix_time::time_duration& d);
00221 };
00222
00223 extern ROSTIME_DECL const Time TIME_MAX;
00224 extern ROSTIME_DECL const Time TIME_MIN;
00225
00231 class ROSTIME_DECL WallTime : public TimeBase<WallTime, WallDuration>
00232 {
00233 public:
00234 WallTime()
00235 : TimeBase<WallTime, WallDuration>()
00236 {}
00237
00238 WallTime(uint32_t _sec, uint32_t _nsec)
00239 : TimeBase<WallTime, WallDuration>(_sec, _nsec)
00240 {}
00241
00242 explicit WallTime(double t) { fromSec(t); }
00243
00247 static WallTime now();
00248
00252 static bool sleepUntil(const WallTime& end);
00253
00254 static bool isSystemTime() { return true; }
00255 };
00256
00257 ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const Time &rhs);
00258 ROSTIME_DECL std::ostream &operator <<(std::ostream &os, const WallTime &rhs);
00259 }
00260
00261 #endif // ROS_TIME_H
00262