Contents
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()
Get the current time as either a rospy.Time instance. rospy.Time.now() and rospy.get_rostime() are equivalent.
rospy.get_time()
Get the current time in float seconds.
seconds = 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)
Create a new Time instance. secs and nsecs are optional and default to zero.
epoch = rospy.Time() # secs=nsecs=0 t = rospy.Time(10) # t.secs=10 t = rospy.Time(12345, 6789)
rospy.Time.from_sec(float_secs)
Create a new Time instance from a float seconds value (same as Python's time.time() representation).
t = rospy.Time.from_sec(123456.789)
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.
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:
1 hour + 1 hour = 2 hours (duration + duration = duration)
2 hours - 1 hour = 1 hour (duration - duration = duration)
Today + 1 day = tomorrow (time + duration = time)
Today - tomorrow = -1 day (time - time = duration)
Today + tomorrow = error (time + time is undefined)
Arithmetic with Time and Duration instances is similar to the above examples:
Sleeping and Rates
rospy.sleep(duration)
duration can either be a rospy.Duration or seconds (float). ROS will sleep for the specified period. sleep() will raise rospy.ROSInterruptException if a terminal condition like node shutdown occurs.
rospy.Rate(hz)
rospy provides a rospy.Rate convenience class which makes a best effort at maintaining a particular rate for a loop. For example:
In the above example, the Rate instance will attempt to keep the loop at 10hz by accounting for the time used by any operations during the loop. Rate.sleep() can throw a rospy.ROSInterruptException if the sleep is interrupted by shutdown.
Timer
New in ROS 1.5+
rospy.Timer(period, callback, oneshot=False)
Introduced in ROS 1.5, rospy provides a rospy.Timer convenience class which periodically calls a callback. Timer is similar to roscpp's Timer class. The arguments to the constructor are:
period
This is the period between calls to the timer callback. For example, if this is rospy.Duration(0.1), the callback will be scheduled for every 1/10th of a second.
callback
This is the function to be called. The function is passed a TimerEvent instance, which is explained below.
oneshot
- Specifies whether or not the timer is a one-shot timer. If so, it will only fire once. Otherwise it will be re-scheduled continuously until it is stopped.
For example:
In the above example, the Timer instance will attempt to call the callback every 2 seconds.
The callback is passed a TimerEvent object which includes the following fields:
rospy.timer.TimerEvent
last_expected
- In a perfect world, this is when the previous callback should have happened.
last_real
- This is when the last callback actually happened.
current_expected
- In a perfect world, this is when the current callback should have been called.
current_real
When the current callback is actually being called (rospy.Time.now() as of immediately before calling the callback.)
last_duration
- Contains the duration of the last callback (end time minus start time) in seconds. Note that this is always in wall-clock time.
To stop the Timer from firing, call shutdown().