Time representation. May either represent wall clock time or ROS clock time. More...
#include <time.h>
Public Member Functions | |
Time () | |
Time (uint32_t _sec, uint32_t _nsec) | |
Time (double t) | |
Static Public Member Functions | |
static Time | fromBoost (const boost::posix_time::ptime &t) |
static Time | fromBoost (const boost::posix_time::time_duration &d) |
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 () |
Wait for time to become valid. | |
static bool | waitForValid (const ros::WallDuration &timeout) |
Wait for time to become valid, with timeout. |
Time representation. May either represent wall clock time or ROS clock time.
ros::TimeBase provides most of its functionality.
ros::Time::Time | ( | ) | [inline] |
ros::Time::Time | ( | uint32_t | _sec, |
uint32_t | _nsec | ||
) | [inline] |
ros::Time::Time | ( | double | t | ) | [inline, explicit] |
Time ros::Time::fromBoost | ( | const boost::posix_time::ptime & | t | ) | [static] |
Definition at line 314 of file src/time.cpp.
Time ros::Time::fromBoost | ( | const boost::posix_time::time_duration & | d | ) | [static] |
Definition at line 320 of file src/time.cpp.
void ros::Time::init | ( | ) | [static] |
Definition at line 271 of file src/time.cpp.
bool ros::Time::isSimTime | ( | ) | [static] |
Definition at line 233 of file src/time.cpp.
bool ros::Time::isSystemTime | ( | ) | [static] |
Definition at line 238 of file src/time.cpp.
bool ros::Time::isValid | ( | ) | [static] |
Returns whether or not the current time is valid. Time is valid if it is non-zero.
Definition at line 283 of file src/time.cpp.
Time ros::Time::now | ( | ) | [static] |
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.
Definition at line 243 of file src/time.cpp.
void ros::Time::setNow | ( | const Time & | new_now | ) | [static] |
Definition at line 263 of file src/time.cpp.
void ros::Time::shutdown | ( | ) | [static] |
Definition at line 278 of file src/time.cpp.
bool ros::Time::sleepUntil | ( | const Time & | end | ) | [static] |
Sleep until a specific time has been reached.
Definition at line 353 of file src/time.cpp.
bool ros::Time::useSystemTime | ( | ) | [static] |
Definition at line 228 of file src/time.cpp.
bool ros::Time::waitForValid | ( | ) | [static] |
Wait for time to become valid.
Definition at line 288 of file src/time.cpp.
bool ros::Time::waitForValid | ( | const ros::WallDuration & | timeout | ) | [static] |
Wait for time to become valid, with timeout.
Definition at line 293 of file src/time.cpp.