$search
Time representation. May either represent wall clock time or ROS clock time. More...
#include <time.h>
Public Member Functions | |
Time (double t) | |
Time (uint32_t _sec, uint32_t _nsec) | |
Time () | |
Static Public Member Functions | |
static void | init () |
static bool | isSimTime () |
static bool | isSystemTime () |
static bool | isValid () |
Returns whether or not the current time is valid. Time is valid if it is non-zero. | |
static Time | now () |
Retrieve the current time. If ROS clock time is in use, this returns the time according to the ROS clock. Otherwise returns the current wall clock time. | |
static void | setNow (const Time &new_now) |
static void | shutdown () |
static bool | sleepUntil (const Time &end) |
Sleep until a specific time has been reached. | |
static bool | useSystemTime () |
static bool | waitForValid (const ros::WallDuration &timeout) |
Wait for time to become valid, with timeout. | |
static bool | waitForValid () |
Wait for time to become valid. |
Time representation. May either represent wall clock time or ROS clock time.
ros::TimeBase provides most of its functionality.
Definition at line 168 of file time.h.
bool ros::Time::isValid | ( | ) | [static] |
Time ros::Time::now | ( | ) | [static] |
bool ros::Time::sleepUntil | ( | const Time & | end | ) | [static] |
bool ros::Time::waitForValid | ( | const ros::WallDuration & | timeout | ) | [static] |
bool ros::Time::waitForValid | ( | ) | [static] |