35 #ifndef ROS_TIME_H_INCLUDED 36 #define ROS_TIME_H_INCLUDED 45 #pragma warning(disable: 4244) 46 #pragma warning(disable: 4661) 52 #include "../../../cpp_common/include/ros/platform.h" 55 #include "../../../cpp_common/include/ros/exception.h" 65 #include <sys/timeb.h> 93 :
Exception(
"Cannot use rs2rosinternal::Time::now() before the first NodeHandle has been created or rs2rosinternal::start() has been called. " 94 "If this is a standalone app or test that just uses rs2rosinternal::Time and does not communicate over ROS, you may also call rs2rosinternal::Time::init()")
107 :
Exception(
"This windows platform does not " 108 "support the high-performance timing api.")
128 template<
class T,
class D>
145 T& operator-=(
const D &rhs);
147 inline bool operator!=(
const T &rhs)
const {
return !(*
static_cast<const T*
>(
this) == rhs); }
153 double toSec()
const {
return (
double)sec + 1
e-9*(double)nsec; };
155 sec =
static_cast<uint32_t>(floor(t));
156 nsec =
static_cast<uint32_t>(round((t-sec) * 1e9));
158 sec +=
static_cast<uint32_t>((nsec / 1000000000ul));
159 nsec %= 1000000000ul;
160 return *
static_cast<T*
>(
this);
166 inline bool isZero()
const {
return sec == 0 && nsec == 0; }
167 inline bool is_zero()
const {
return isZero(); }
188 explicit Time(
double t) { fromSec(t); }
199 static bool sleepUntil(
const Time&
end);
202 static void shutdown();
203 static void setNow(
const Time& new_now);
204 static bool useSystemTime();
205 static bool isSimTime();
206 static bool isSystemTime();
211 static bool isValid();
215 static bool waitForValid();
ROSTIME_DECL void normalizeSecNSec(uint64_t &sec, uint64_t &nsec)
bool operator==(const plane &lhs, const plane &rhs)
ROSTIME_DECL const Time TIME_MAX
Thrown if the ros subsystem hasn't been initialised before use.
Base class for Time implementations. Provides storage, common functions and operator overloads...
bool operator>(failed, failed)
Time(uint32_t _sec, uint32_t _nsec)
Duration representation for use with the Time class.
ImVec4 operator+(const ImVec4 &c, float v)
Duration representation for use with the WallTime class.
Base class for all exceptions thrown by ROS.
ROSTIME_DECL void normalizeSecNSecUnsigned(int64_t &sec, int64_t &nsec)
float3 operator-(const float3 &a, const float3 &b)
bool operator!=(const T &rhs) const
bool operator<(failed, failed)
Time representation. Always wall-clock time.
Time representation. May either represent wall clock time or ROS clock time.
unsigned __int64 uint64_t
auto operator+=(std::string &lhs, StringRef const &sr) -> std::string &
std::ostream & operator<<(std::ostream &os, const Duration &rhs)
TimeBase(uint32_t _sec, uint32_t _nsec)
ROSTIME_DECL const Time TIME_MIN
GLbitfield GLuint64 timeout
TimeNotInitializedException()
bool operator>=(failed, failed)
static bool isSystemTime()
WallTime(uint32_t _sec, uint32_t _nsec)
bool operator<=(failed, failed)