Skip to content

ROS 2 Migration: ROS Clocks and sim time

Jacob Perron edited this page May 17, 2022 · 14 revisions

Overview

This pages describes simulation time in ROS 2, which works very similarly to simulation time in ROS 1.

While on ROS 1 all time functionality was provided by a system plugin called gazebo_ros_api_plugin, on ROS 2, it's been moved to a plugin called gazebo_ros_init.

These are the provided interfaces:

Name Message / Service Definition Description
/clock Message rosgraph_msgs::msg::Clock Publishes simulation time.
pause_physics Service std_srvs::srv::Empty Pauses simulation.
unpause_physics Service std_srvs::srv::Empty Unpauses simulation.
reset_simulation Service std_srvs::srv::Empty Reset time and model states.
reset_world Service std_srvs::srv::Empty Reset model states.

Sim time

As in ROS 1, nodes in ROS 2 can be configured to use ROS time, which is fed by an external source publishing to the /clock topic, such as a simulator or data playback. See this article for more details.

To enable use of the simulation time for a ROS 2 node's clock, the node should have the use_sim_time parameter set on it. However, gazebo_ros_plugins will continue to use simulation time header for sensor messages and transforms, since timestamp mismatches in sensor messages can lead to issues with SLAM algorithms. Please refer to this issue and the relevant pull request for further details.

The clock publisher

The gazebo_ros_init plugin publishes the current time of the Gazebo simulation to the /clock topic.

To enable time publishing, you can load the plugin as Gazebo is launched using the -s option, i.e.:

gazebo -s libgazebo_ros_init.so

Coming up: This plugin will be loaded automatically from gazebo_ros launch files

You can check time is being published correctly by echoing the /clock topic:

ros2 topic echo /clock

The publisher's Quality of Service settings are configured with a queue depth of 10 and transient local durability (see this page for details).

No messages will be published to the /clock topic if the simulation is paused (this is the same in ROS 1). Subscribers can opt to receive the previously-published time message(s) when the simulation is paused by requesting transient local durability in their Quality of Service settings.

Clock rate

On ROS 1, the clock publish rate was controller by the pub_clock_frequency parameter on gazebo_ros_api_plugin.

On ROS 2, by default, the /clock topic is published at 10 Hz. The publish_rate ROS parameter can be used to adjust that

For example, given the following parameter file (params.yaml):

gazebo:
    ros__parameters:
        publish_rate: 1.0

And starting Gazebo as follows:

gazebo -s libgazebo_ros_init.so --ros-args --params-file params.yaml

Alternatively a one-liner can be used:

gazebo -s libgazebo_ros_init.so --ros-args -p -publish_rate:=100.0

Another option is provided for integration with ros2/launch, i.e

ros2 launch gazebo_ros gzserver.launch.py extra_gazebo_args:="--ros-args --params-file params.yaml"

A params_file shorthand is also provided:

ros2 launch gazebo_ros gazebo.launch.py params_file:=params.yml

It can be checked that the rate is now 1 Hz:

ros2 topic hz /clock

Time commands

Gazebo must be launched with the gazebo_ros_init plugin for features like pausing and resetting to be enabled.

You can try it as follows:

  1. Launch Gazebo:

    gazebo -s libgazebo_ros_init.so

  2. On a new terminal, echo simulation time and see it is increasing:

    ros2 topic echo /clock

  3. On a new terminal, request pause and note that sim time stops increasing:

    ros2 service call /pause_physics std_srvs/Empty

  4. Then request unpause and note that sim time starts increasing again:

    ros2 service call /unpause_physics std_srvs/Empty

  5. Now request to reset simulation and see that time returns to zero:

    ros2 service call /reset_simulation std_srvs/Empty

  6. To test the reset_world service, first insert a box in simulation using the Gazebo GUI's top toolbar.

  7. We want the box to move, so let's delete the ground plane by right-clicking it on the left menu and choosing delete. The box will start falling.

  8. Now we can reset the box's pose, but not sim time, as follows. Note how the box comes back up and starts falling again:

    ros2 service call /reset_world std_srvs/Empty