[Documentation] [TitleIndex] [WordIndex

Time and Duration

See also: ros::TimeBase API docs, ros::DurationBase API docs

ROS has builtin time and duration primitive types, which roslib provides as the ros::Time and ros::Duration classes, respectively. A Time is a specific moment (e.g. "today at 5pm") whereas a Duration is a period of time (e.g. "5 hours"). Durations can be negative.

Times and durations have identical representations:

int32 sec
int32 nsec

Time cannot be negative, while durations can hold both positive and negative values (represented by negative sec; nsec is always non-negative). Beware that negative durations interpret sec and nsec so that float_time = sec + nsec * 10e-9, so e.g. a duration instance with sec = -1, nsec = 5e8 represents a duration of -0.5 seconds and not -1.5 seconds.

ROS has the ability to setup a simulated Clock for nodes. Instead of using platform time routines, you should use roscpp's time routines for accessing the current time, which will work seamlessly with simulated Clock time as well as wall-clock time.

Getting the Current Time

ros::Time::now()

   1 ros::Time begin = ros::Time::now();

Time zero

When using simulated Clock time, now() returns time 0 until first message has been received on /clock, so 0 means essentially that the client does not know clock time yet. A value of 0 should therefore be treated differently, such as looping over now() until non-zero is returned.

Creating Time and Duration Instances

You can create a Time or Duration to a specific value as well, either floating-point seconds:

   1 ros::Time a_little_after_the_beginning(0.001);
   2 ros::Duration five_seconds(5.0);

or through the two-integer constructor:

   1 ros::Time a_little_after_the_beginning(0, 1000000);
   2 ros::Duration five_seconds(5, 0);

Converting Time and Duration Instances

Time and Duration objects can also be turned into floating point seconds:

   1 double secs =ros::Time::now().toSec();
   2 
   3 ros::Duration d(0.5);
   4 secs = d.toSec();

Time and Duration Arithmetic

Like other primitive types, you can perform arithmetic operations on Times and Durations. People are often initially confused on what arithmetic with these instances is like, so it's good to run through some examples:

Arithmetic with Time and Duration instances is similar to the above examples:

   1 ros::Duration two_hours = ros::Duration(60*60) + ros::Duration(60*60);
   2 ros::Duration one_hour = ros::Duration(2*60*60) - ros::Duration(60*60);
   3 ros::Time tomorrow = ros::Time::now() + ros::Duration(24*60*60);
   4 ros::Duration negative_one_day = ros::Time::now() - tomorrow;

Sleeping and Rates

bool ros::Duration::sleep()

ros::Rate

Wall Time

For cases where you want access to the actual wall-clock time even if running inside simulation, roslib provides Wall versions of all its time constructs, i.e. ros::WallTime, ros::WallDuration, and ros::WallRate which have identical interfaces to ros::Time, ros::Duration, and ros::Rate respectively.


2024-11-16 17:43