[Documentation] [TitleIndex] [WordIndex

Introduction

Normally, the ROS client libraries will use your computer's system clock as a time source, also known as the "wall-clock" or "wall-time" (like the clock on the wall of your lab). When you are running a simulation or playing back logged data, however, it is often desirable to instead have the system use a simulated clock so that you can have accelerated, slowed, or stepped control over your system's perceived time. For example, if you are playing back sensor data into your system, you may wish to have your time correspond to the timestamps of the sensor data.

To support this, the ROS client libraries can listen to the /clock topic that is used to publish "simulation time".

In order for your code to take advantage of the ROS simulation time, it is important that all code use the appropriate ROS client library Time API for accessing time and sleeping instead of using the language-native routines. This will allow your system to have a consistent time measurement whether it is using the wall-clock or a simulated clock. These APIs are described briefly below, though you should familiarize yourself with your client library of choice for more details.

When using wall-clock time on multiple machines, it is important that you synchronize time between them. ROS does not provide this functionality as there are already well-established methods (e.g. ntp, our recommended syncronization tool is chrony) for doing this. If you do not synchronize the wall-clocks of multiple machines, they will not agree on temporal calculations like those used in tf.

NOTE: this is not an API for real-time systems!

Using Simulation Time from the /clock Topic

In order for a ROS node to use simulation time according to the /clock topic, the /use_sim_time parameter must be set to true before the node is initialized. This can be done in a launchfile or from the command line.

If the /use_sim_time parameter is set, the ROS Time API will return time=0 until it has received a value from the /clock topic. Then, the time will only be updated on receipt of a message from the /clock topic, and will stay constant between updates.

For calculations of time durations when using simulation time, clients should always wait until the first non-zero time value has been received before starting, because the first simulation time value from /clock topic may be a high value.

Note: Prior to ROS C Turtle, nodes were automatically subscribed to the /clock topic, and would use simulation time if there was anything published to the /clock topic.

Running a Clock Server

A Clock Server is any node that publishes to the /clock topic, and there should never be more than one running in a single ROS network. In most cases, the Clock Server is either a simulator or a log playback tool.

In order to resolve any issues with startup order, it is important that the /use_sim_time Parameter is set to true in any launch files using a Clock Server. If you are playing back a bag file with rosbag play, using the --clock option will run a Clock Server while the bag file is being played.

Clock Message

roslib/Clock (Up to C Turtle)

rosgraph_msgs/Clock (Diamondback and later):

time clock

Client Libraries

Here are some simple examples of the ROS Time API use in three of the main client libraries.

Note: For more documentation, please consult the "Code API" of the relevant ROS Client Library Package listed below.

C++ (roscpp) Time API

//Get the time and store it in the time variable.
ros::Time time = ros::Time::now();
//Wait a duration of one second.
ros::Duration d = ros::Duration(1, 0);
d.sleep();

Python (rospy) Time API

rospy.get_rostime() #get time as rospy.Time instance
rospy.get_time() #get time as float secs
rospy.sleep(duration)

LISP (roslisp) Time API

(ros-time)

2024-11-16 12:14