ROS Clock#
Learning Objectives#
In this example, we will
Have a brief discussion on the ROS Clock publisher and subscriber
Publish simulation time to ROS as a Clock message
Subscribe to a ROS Clock message
Getting Started#
Prerequisite
Completed ROS and ROS 2 Installation: installed ROS, enabled the ROS extension, built the provided Isaac Sim ROS workspace, and set up the necessary environment variables .
It is also helpful to have some basic understanding of ROS topics and how publisher and subscriber works.
ROS Bridge is enabled.
roscore
is running.
Simulation Time and Clock#
In order for external ROS nodes to synchronize with simulation time, a clock topic is usually used. Many ROS nodes such as RViz use the parameter use_sim_time
which if set to True will indicate to the node to begin subscribing to the /clock
topic and synchronizing to the published simulation time. This parameter can be set using a ROS launch file or the command line interface. We will later see how we can set this parameter in the terminal and observe the effect it has on certain ROS nodes.
Running ROS Clock Publisher#
Go to Create -> Visual Scripting -> Action Graph to create an Action graph.
Add the following OmniGraph nodes into the Action graph:
On Playback Tick node to execute other graph nodes every simulation frame.
Isaac Read Simulation Time node to retrieve current simulation time. Note: By default the simulation time increases monotonically, meaning regardless of whether simulation is stopped and re-played, the time will continue incrementing. This is mainly to prevent issues that may aries with the time jumping back when simulation resets. You can set
resetOnStop
to True if you would like the clock to start from 0 every time simulation is reset.ROS1 Publish Clock node to publish simulation time to the
/clock
topic.
Start RViz in a new ROS-sourced terminal.
rosrun rviz rviz
Take note of the ROS Time and ROS Elapsed times listed in the bottom of the RViz window. These are currently displaying the wall time and should match the Wall Time and Wall Elapsed fields.
In a new ROS-sourced terminal set the
use_sim_time
parameter to true for the RViz node using the following command. Ensure that simulation is stopped in Isaac Sim.rosparam set /use_sim_time true
Close and reopen RViz. Notice this time in RViz that ROS Time and ROS Elapsed are now both 0.
In Isaac Sim click Play. In RViz, the ROS Time is now identical to the simulation time published from Isaac Sim over the
/clock
topic.
Publishing System Time#
While publishing the simulation time is the most common workflow, there may be certain workflows that require certain messages to contain system time. To publish system time over the clock topic follow these steps:
Go to Create -> Visual Scripting -> Action Graph to create an Action graph.
Add the following OmniGraph nodes into the Action graph:
On Playback Tick node to execute other graph nodes every simulation frame.
Isaac Read System Time node to retrieve current system time.
ROS1 Publish Clock node to publish simulation time to the
/clock
topic.
In Isaac Sim click Play. To see the system timestamp published from Isaac Sim over the
/clock
topic run the following command in a ROS-sourced terminal:rostopic echo /clock
Camera Helper and RTX Lidar nodes
You have already seen the ROS Camera Helper node in a previous tutorial and you will see the ROS RTX Lidar Helper node in a following tutorial. As both of these nodes automatically generate a sensor publishing pipeline, to use system timestamps for their publishers, ensure that their useSystemTime
input is set to True.
Running ROS Clock Subscriber#
Open a new stage. Go to Create -> Visual Scripting -> Action Graph to create an Action graph.
Add the following OmniGraph nodes into the Action graph:
On Playback Tick node to execute other graph nodes every simulation frame.
ROS1 Subscribe Clock node to subscribe to external timestamp data.
Start simulation by clicking Play. Select the ROS1 Subscribe Clock node inside the action graph to view its
timeStamp
output in the Property window. The timestamp should be currently 0.In a new ROS-sourced terminal run the following command to manually publish a clock message once:
rostopic pub -1 /clock rosgraph_msgs/Clock "clock: { secs: 1, nsecs: 200000000 }"
The
timeStamp
value in the ROS1 Subscribe Clock OmniGraph node should change to 1.2.Change the previous command with different secs and nsecs values to see those values being reflected in the
timeStamp
field of the ROS1 Subscribe Clock OmniGraph node.
Summary#
This tutorial covered
Explanation for using the
/clock
topic and theuse_sim_time
ROS parameter for time synchronization.Creating and using ROS Clock Publisher and Subscriber nodes.
Next Steps#
Continue on to the next tutorial in our ROS Tutorials series, RTX Lidar Sensors, to learn how to add a Lidar sensor to the Turtlebot3.