Public Member Functions | Static Public Member Functions
ros::Time Class Reference

Time representation. May either represent wall clock time or ROS clock time. More...

#include <time.h>

Inheritance diagram for ros::Time:
Inheritance graph
[legend]

List of all members.

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.

Detailed Description

Time representation. May either represent wall clock time or ROS clock time.

ros::TimeBase provides most of its functionality.

Definition at line 169 of file time.h.


Constructor & Destructor Documentation

ros::Time::Time ( ) [inline]

Definition at line 172 of file time.h.

ros::Time::Time ( uint32_t  _sec,
uint32_t  _nsec 
) [inline]

Definition at line 176 of file time.h.

ros::Time::Time ( double  t) [inline, explicit]

Definition at line 180 of file time.h.


Member Function Documentation

Time ros::Time::fromBoost ( const boost::posix_time::ptime &  t) [static]

Definition at line 314 of file time.cpp.

Time ros::Time::fromBoost ( const boost::posix_time::time_duration &  d) [static]

Definition at line 320 of file time.cpp.

void ros::Time::init ( ) [static]

Definition at line 271 of file time.cpp.

bool ros::Time::isSimTime ( ) [static]

Definition at line 233 of file time.cpp.

bool ros::Time::isSystemTime ( ) [static]

Definition at line 238 of file 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 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 time.cpp.

void ros::Time::setNow ( const Time new_now) [static]

Definition at line 263 of file time.cpp.

void ros::Time::shutdown ( ) [static]

Definition at line 278 of file time.cpp.

bool ros::Time::sleepUntil ( const Time end) [static]

Sleep until a specific time has been reached.

Definition at line 346 of file time.cpp.

bool ros::Time::useSystemTime ( ) [static]

Definition at line 228 of file time.cpp.

bool ros::Time::waitForValid ( ) [static]

Wait for time to become valid.

Definition at line 288 of file 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 time.cpp.


The documentation for this class was generated from the following files:


rostime
Author(s): Josh Faust
autogenerated on Fri Jan 3 2014 11:49:59