[Documentation] [TitleIndex] [WordIndex

Time and Duration

ROS has builtin time and duration primitive types, which rospy provides as the rospy.Time and rospy.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 secs
int32 nsecs

ROS has the ability to setup a simulated Clock for nodes. Instead of using Python's time.time module, you should use rospy'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

rospy.Time.now(), rospy.get_rostime()

rospy.get_time()

Time zero

When using simulated Clock time, get_rostime() 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 get_rostime() until non-zero is returned.

Creating Time instances

There are a variety of ways of creating new Time instances in addition to the methods above for getting the current time.

rospy.Time(secs=0, nsecs=0)

rospy.Time.from_sec(float_secs)

Converting Time and Duration instances

Time and Duration instances can be converted to seconds as well as nanoseconds for easy use with non-ROS libraries.

   1 t = rospy.Time.from_sec(time.time())
   2 seconds = t.to_sec() #floating point
   3 nanoseconds = t.to_nsec()
   4 
   5 d = rospy.Duration.from_sec(60.1)  # One minute and one tenth of a second
   6 seconds = d.to_sec() #floating point
   7 nanoseconds = d.to_nsec()

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 two_hours = rospy.Duration(60*60) + rospy.Duration(60*60)
   2 one_hour = rospy.Duration(2*60*60) - rospy.Duration(60*60)
   3 tomorrow = rospy.Time.now() + rospy.Duration(24*60*60)
   4 negative_one_day = rospy.Time.now() - tomorrow

Sleeping and Rates

rospy.sleep(duration)

rospy.Rate(hz)

Timer

New in ROS 1.5+

rospy.Timer(period, callback, oneshot=False)


2024-11-16 17:44