Public Member Functions | Static Public Member Functions | List of all members
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]

Public Member Functions

 Time ()
 
 Time (double t)
 
 Time (uint32_t _sec, uint32_t _nsec)
 
- Public Member Functions inherited from ros::TimeBase< Time, Duration >
TimefromNSec (uint64_t t)
 
TimefromSec (double t)
 
bool is_zero () const
 
bool isZero () const
 
const Time MAX
 
const WallTime MAX
 
const SteadyTime MAX
 
const Time MAX
 
const WallTime MAX
 
const SteadyTime MAX
 
const Time MIN
 
const WallTime MIN
 
const SteadyTime MIN
 
const Time MIN
 
const WallTime MIN
 
const SteadyTime MIN
 
bool operator!= (const Time &rhs) const
 
Time operator+ (const Duration &rhs) const
 
Timeoperator+= (const Duration &rhs)
 
Time operator- (const Duration &rhs) const
 
Duration operator- (const Time &rhs) const
 
Timeoperator-= (const Duration &rhs)
 
bool operator< (const Time &rhs) const
 
bool operator<= (const Time &rhs) const
 
bool operator== (const Time &rhs) const
 
bool operator> (const Time &rhs) const
 
bool operator>= (const Time &rhs) const
 
 TimeBase ()
 
 TimeBase (double t)
 
 TimeBase (uint32_t _sec, uint32_t _nsec)
 
boost::posix_time::ptime toBoost () const
 
uint64_t toNSec () const
 
double toSec () const
 
const Time UNINITIALIZED
 
const WallTime UNINITIALIZED
 
const SteadyTime UNINITIALIZED
 
const Time UNINITIALIZED
 
const WallTime UNINITIALIZED
 
const SteadyTime UNINITIALIZED
 
const Time ZERO
 
const WallTime ZERO
 
const SteadyTime ZERO
 
const Time ZERO
 
const WallTime ZERO
 
const SteadyTime ZERO
 

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 source is valid. Simulation time is valid if it is non-zero. More...
 
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. More...
 
static void setNow (const Time &new_now)
 
static void shutdown ()
 
static bool sleepUntil (const Time &end)
 Sleep until a specific time has been reached. More...
 
static bool useSystemTime ()
 
static bool waitForValid ()
 Wait for time source to become valid. More...
 
static bool waitForValid (const ros::WallDuration &timeout)
 Wait for time source to become valid, with timeout. More...
 

Additional Inherited Members

- Public Attributes inherited from ros::TimeBase< Time, Duration >
uint32_t nsec
 
uint32_t sec
 
- Static Public Attributes inherited from ros::TimeBase< Time, Duration >
static const Time MAX
 Maximum representable time. More...
 
static const Time MIN
 Minimum representable time. More...
 
static const Time UNINITIALIZED
 Uninitialized time. More...
 
static const Time ZERO
 Zero (invalid) time. More...
 

Detailed Description

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

ros::TimeBase provides most of its functionality.

Definition at line 174 of file time.h.

Constructor & Destructor Documentation

◆ Time() [1/3]

ros::Time::Time ( )
inline

Definition at line 177 of file time.h.

◆ Time() [2/3]

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

Definition at line 181 of file time.h.

◆ Time() [3/3]

ros::Time::Time ( double  t)
inlineexplicit

Definition at line 185 of file time.h.

Member Function Documentation

◆ fromBoost() [1/2]

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

Definition at line 331 of file src/time.cpp.

◆ fromBoost() [2/2]

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

Definition at line 337 of file src/time.cpp.

◆ init()

void ros::Time::init ( )
static

Definition at line 288 of file src/time.cpp.

◆ isSimTime()

bool ros::Time::isSimTime ( )
static

Definition at line 250 of file src/time.cpp.

◆ isSystemTime()

bool ros::Time::isSystemTime ( )
static

Definition at line 255 of file src/time.cpp.

◆ isValid()

bool ros::Time::isValid ( )
static

Returns whether or not the current time source is valid. Simulation time is valid if it is non-zero.

Definition at line 300 of file src/time.cpp.

◆ now()

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 260 of file src/time.cpp.

◆ setNow()

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

Definition at line 280 of file src/time.cpp.

◆ shutdown()

void ros::Time::shutdown ( )
static

Definition at line 295 of file src/time.cpp.

◆ sleepUntil()

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

Sleep until a specific time has been reached.

Returns
True if the desired sleep time was met, false otherwise.

Definition at line 373 of file src/time.cpp.

◆ useSystemTime()

bool ros::Time::useSystemTime ( )
static

Definition at line 245 of file src/time.cpp.

◆ waitForValid() [1/2]

bool ros::Time::waitForValid ( )
static

Wait for time source to become valid.

Definition at line 305 of file src/time.cpp.

◆ waitForValid() [2/2]

bool ros::Time::waitForValid ( const ros::WallDuration timeout)
static

Wait for time source to become valid, with timeout.

Definition at line 310 of file src/time.cpp.


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


rostime
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sat Jun 17 2023 02:32:37