35 #ifndef ROS_TIME_H_INCLUDED 36 #define ROS_TIME_H_INCLUDED 45 #pragma warning(disable: 4244) 46 #pragma warning(disable: 4661) 58 #include <boost/math/special_functions/round.hpp> 66 #include <sys/timeb.h> 72 namespace posix_time {
92 :
Exception(
"Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. " 93 "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()")
106 :
Exception(
"This windows platform does not " 107 "support the high-performance timing api.")
129 template<
class T,
class D>
136 TimeBase(uint32_t _sec, uint32_t _nsec) : sec(_sec), nsec(_nsec)
141 D operator-(
const T &rhs)
const;
142 T operator+(
const D &rhs)
const;
143 T operator-(
const D &rhs)
const;
144 T& operator+=(
const D &rhs);
145 T& operator-=(
const D &rhs);
146 bool operator==(
const T &rhs)
const;
147 inline bool operator!=(
const T &rhs)
const {
return !(*
static_cast<const T*
>(
this) == rhs); }
148 bool operator>(
const T &rhs)
const;
149 bool operator<(
const T &rhs)
const;
150 bool operator>=(
const T &rhs)
const;
151 bool operator<=(
const T &rhs)
const;
153 double toSec()
const {
return static_cast<double>(sec) + 1e-9*static_cast<double>(nsec); };
154 T& fromSec(
double t);
156 uint64_t
toNSec()
const {
return static_cast<uint64_t
>(sec)*1000000000ull + static_cast<uint64_t>(nsec); }
157 T& fromNSec(uint64_t t);
159 inline bool isZero()
const {
return sec == 0 && nsec == 0; }
160 inline bool is_zero()
const {
return isZero(); }
161 boost::posix_time::ptime toBoost()
const;
177 Time(uint32_t _sec, uint32_t _nsec)
181 explicit Time(
double t) { fromSec(t); }
192 static bool sleepUntil(
const Time& end);
195 static void shutdown();
196 static void setNow(
const Time& new_now);
197 static bool useSystemTime();
198 static bool isSimTime();
199 static bool isSystemTime();
204 static bool isValid();
208 static bool waitForValid();
214 static Time fromBoost(
const boost::posix_time::ptime& t);
215 static Time fromBoost(
const boost::posix_time::time_duration& d);
248 static bool sleepUntil(
const WallTime& end);
282 static bool sleepUntil(
const SteadyTime& end);
ROSTIME_DECL std::ostream & operator<<(std::ostream &os, const SteadyTime &rhs)
static bool isSystemTime()
ROSTIME_DECL void ros_steadytime(uint32_t &sec, uint32_t &nsec)
Time representation. May either represent wall clock time or ROS clock time.
WallTime(uint32_t _sec, uint32_t _nsec)
ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t &sec, int64_t &nsec)
bool operator!=(const T &rhs) const
TimeNotInitializedException()
SteadyTime(uint32_t _sec, uint32_t _nsec)
TimeBase(uint32_t _sec, uint32_t _nsec)
Duration representation for use with the WallTime class.
Thrown if the ros subsystem hasn't been initialised before use.
ROSTIME_DECL void ros_walltime(uint32_t &sec, uint32_t &nsec)
Time(uint32_t _sec, uint32_t _nsec)
Base class for Time implementations. Provides storage, common functions and operator overloads...
Time representation. Always wall-clock time.
ROSTIME_DECL void normalizeSecNSec(uint32_t &sec, uint32_t &nsec)
ROSTIME_DECL const Time TIME_MAX
Time representation. Always steady-clock time.
static bool isSystemTime()
ROSTIME_DECL const Time TIME_MIN
Duration representation for use with the Time class.