Reasoning behind different types of simulation time when publishing ROS messages

Isaac Sim Version

4.5.0
4.2.0
4.1.0
4.0.0
4.5.0
2023.1.1
2023.1.0-hotfix.1
Other (please specify):

Operating System

Ubuntu 22.04
Ubuntu 20.04
Windows 11
Windows 10
Other (please specify):

GPU Information

  • Model: A40-48Q
  • Driver Version: 550.127.05

Topic Description

Detailed Description

I am figuring out how timestamps are set when I use the ROS2CamerHelper node in order to publish images via ROS. I use exactly the setup from the tutorial: ROS2 Cameras — Isaac Sim Documentation

The generated message timestamps are confusing, they don’t seem to reflect what I consider the acutal simulation time.

Steps to Reproduce

  1. Set up a stage like in the tutorial using the graph shortcut.
  2. Make sure the stage’s time codes per second is set to the default 60.
  3. Start the simulation.
  4. Use a terminal with sourced ROS environment and display timestamps like this: ros2 topic echo /rgb|grep sec
  5. Note that timestamps increase by about 1/60 seconds for each message
    ...
    sec: 3
    nanosec: 156
    sec: 3
    nanosec: 16666823
    sec: 3
    nanosec: 33333491
    sec: 3
    nanosec: 50000159
    sec: 3
    nanosec: 66666826
    sec: 3
    nanosec: 83333494
    sec: 3
    nanosec: 100000161
    sec: 3
    nanosec: 116666829
    ...
  1. Change the time codes per second setting to 50 in the layer settings.
  2. Save and reload the stage
  3. Run the simulation again
  4. Note that the timestamps increase in an unregular way, by 1/30 and 1/60 seconds:
    ...
    sec: 7
    nanosec: 365
    sec: 7
    nanosec: 16667032
    sec: 7
    nanosec: 50000367
    sec: 7
    nanosec: 66667035
    sec: 7
    nanosec: 83333702
    sec: 7
    nanosec: 100000370
    sec: 7
    nanosec: 116667037
    sec: 7
    nanosec: 150000372
    sec: 7
    nanosec: 166667040
    sec: 7
    nanosec: 183333707
    ...
  1. Create a physics scene in the stage and set the time steps of the physics scene to 50
  2. Save and reload the scene and restart the simulation
  3. Note that now the timestamps look like expected:
    ...
    sec: 2
    nanosec: 999999932
    sec: 3
    nanosec: 19999932
    sec: 3
    nanosec: 39999932
    sec: 3
    nanosec: 59999931
    sec: 3
    nanosec: 79999931
    sec: 3
    nanosec: 99999930
    ...
  1. While pausing the simulation, modify the SDGPipeline graph and print the output of the “Isaac Read Simulation Time” node.
  2. Note that the “Isaac Read Simulation Time” node output seems to represent the frequency set in the physics scene, not the frequency set in the stage’s time codes per second.
  3. Note that the timestamps created in the ROS messages do not reflect the time stepping of the simulation timeline.

hi @bruno.vetter, are you trying to control the timestamp on the ROS messages? The Read Simulation Time node can be useful for checking if there is any discrepancy between the published and simulation timestamp. Is that helpful?

Hello @rchadha, thanks for your suggestion. I modified the SDGPipeline graph to print the output from the “Read Simulation Time” node (printed with info loglevel) next to the simulation time taken from the “Get main timeline” node (printed with warning loglevel).

The output is as follows:

2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.25
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.22
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.26667
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.24
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.28333
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.26
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.3
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.28
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.31667
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.3
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.35
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.32
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.36667
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.34
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.38333
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.36
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.4
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.38
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.41667
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.4
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.45
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.42
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.46667
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.44
2025-02-28 07:51:25  [Info] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.48333
2025-02-28 07:51:25  [Warning] [omni.graph.ui_nodes.ogn.nodes.OgnPrintText] 8.46

I have set the USD stage timecodes per second set to 50, while the physics steps per second is not being set, so it should be 60 by default.
Note how the output of the simulation time from the main timeline differs from the output of “Read Simulation Time”.
The main timeline steps are 0.02s as expected, but the weird stepping of “Read simulation time” is what I see in the published ROS messages.

@Ayush_G , can you provide more insight here?