Go to the documentation of this file.
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>
147 inline bool operator!=(
const T &rhs)
const {
return !(*
static_cast<const T*
>(
this) == rhs); }
153 double toSec()
const {
return static_cast<double>(
sec) + 1e-9*
static_cast<double>(
nsec); };
156 uint64_t
toNSec()
const {
return static_cast<uint64_t
>(
sec)*1000000000ull +
static_cast<uint64_t
>(
nsec); }
181 Time(uint32_t _sec, uint32_t _nsec)
185 explicit Time(
double t) { fromSec(t); }
196 static bool sleepUntil(
const Time& end);
199 static void shutdown();
200 static void setNow(
const Time& new_now);
201 static bool useSystemTime();
202 static bool isSimTime();
203 static bool isSystemTime();
208 static bool isValid();
212 static bool waitForValid();
218 static Time fromBoost(
const boost::posix_time::ptime& t);
219 static Time fromBoost(
const boost::posix_time::time_duration& d);
256 static bool sleepUntil(
const WallTime& end);
295 static bool sleepUntil(
const SteadyTime& end);
ROSTIME_DECL void ros_steadytime(uint32_t &sec, uint32_t &nsec)
ROSTIME_DECL void ros_walltime(uint32_t &sec, uint32_t &nsec)
ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t &sec, int64_t &nsec)
bool operator<(const T &rhs) const
ROSTIME_DECL std::ostream & operator<<(std::ostream &os, const Duration &rhs)
bool operator!=(const T &rhs) const
SteadyTime(uint32_t _sec, uint32_t _nsec)
static bool isSystemTime()
static const T MAX
Maximum representable time.
Time(uint32_t _sec, uint32_t _nsec)
Base class for Time implementations. Provides storage, common functions and operator overloads....
Time representation. Always steady-clock time.
static const T ZERO
Zero (invalid) time.
boost::posix_time::ptime toBoost() const
T operator+(const D &rhs) const
bool operator<=(const T &rhs) const
T & operator-=(const D &rhs)
bool operator>(const T &rhs) const
Time representation. Always wall-clock time.
const ROSTIME_DECL Time TIME_MIN
Thrown if the ros subsystem hasn't been initialised before use.
bool operator>=(const T &rhs) const
D operator-(const T &rhs) const
const ROSTIME_DECL Time TIME_MAX
Time representation. May either represent wall clock time or ROS clock time.
static bool isSystemTime()
static const T MIN
Minimum representable time.
static const T UNINITIALIZED
Uninitialized time.
T & operator+=(const D &rhs)
Duration representation for use with the WallTime class.
WallTime(uint32_t _sec, uint32_t _nsec)
Duration representation for use with the Time class.
ROSTIME_DECL void normalizeSecNSec(uint64_t &sec, uint64_t &nsec)
bool operator==(const T &rhs) const
rostime
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sat Jun 17 2023 02:32:37