Go to the documentation of this file.
36 #ifndef ROS_TIME_H_INCLUDED
37 #define ROS_TIME_H_INCLUDED
46 #pragma warning(disable: 4244)
47 #pragma warning(disable: 4661)
54 #include <ros/platform.h>
57 #include <ros/exception.h>
67 #include <sys/timeb.h>
73 namespace posix_time {
93 :
Exception(
"Cannot use ros::Time::now() before the first NodeHandle has been created or ros::start() has been called. "
94 "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()")
107 :
Exception(
"This windows platform does not "
108 "support the high-performance timing api.")
128 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 (
double)
sec + 1e-9*(double)
nsec; };
159 nsec %= 1000000000ul;
160 return *
static_cast<T*
>(
this);
163 uint64_t
toNSec()
const {
return (uint64_t)
sec*1000000000ull + (uint64_t)
nsec; }
184 Time(uint32_t _sec, uint32_t _nsec)
188 explicit Time(
double t) { fromSec(
t); }
199 static bool sleepUntil(
const Time& end);
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();
255 static bool sleepUntil(
const WallTime& end);
Base class for all exceptions thrown by ROS.
bool operator>=(const T &rhs) const
Time representation. Always wall-clock time.
Time representation. May either represent wall clock time or ROS clock time.
bool operator<(const T &rhs) const
static bool isSystemTime()
std::ostream & operator<<(std::ostream &os, const Time &rhs)
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
const Time TIME_MIN(0, 1)
void normalizeSecNSecUnsigned(int64_t &sec, int64_t &nsec)
T operator+(const D &rhs) const
Base class for Time implementations. Provides storage, common functions and operator overloads....
const ROSTIME_DECL Time TIME_MAX
bool operator==(const T &rhs) const
uint32_t nsec(const rosTime &time)
T & operator+=(const D &rhs)
Duration representation for use with the Time class.
bool operator<=(const T &rhs) const
bool operator>(const T &rhs) const
bool operator!=(const T &rhs) const
Duration representation for use with the WallTime class.
uint32_t sec(const rosTime &time)
D operator-(const T &rhs) const
WallTime(uint32_t _sec, uint32_t _nsec)
void normalizeSecNSec(uint64_t &sec, uint64_t &nsec)
Thrown if the ros subsystem hasn't been initialised before use.
Time(uint32_t _sec, uint32_t _nsec)
T & operator-=(const D &rhs)
geometry_msgs::TransformStamped t
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROS initialization function.
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:12