Isaac Sim Version
5.0.0
Operating System
Windows 11
GPU Information
- Model: RTX 3080 Mobile
- Driver Version: 577.0
Topic Description
Detailed Description
2 years ago somebody detected problem when an annotator output is always delayed for 2 frames.
I ran into the same problem when tried to get rendered frames in a graph powered by the On Physics Step node. Actually, there were 2 problems:
- On Physics Step node evaluates an OnDemand graph containing it during the PhysX step event:
// Inside OgnOnPhysicsStep class of isaacsim.core.nodes extension
static void onPhysicsStep(float timeElapsed, void* userData)
{
...
graphObj.iGraph->evaluate(graphObj);
}
static void initialize(const NodeObj& nodeObj, GraphInstanceID instanceId)
{
...
g_graphsWithPhysxStepNode[graphObj.graphHandle].stepSubscription = g_physXInterface->subscribePhysicsOnStepEvents(
false, 0, onPhysicsStep, reinterpret_cast<void*>(&state.m_graphHandlePair));
...
}
static void initInstance(NodeObj const& nodeObj, GraphInstanceID instanceId)
{
initialize(nodeObj, instanceId);
}
Physics is executed before rendering (Pre-Render, Render, Post-Render). Replicator’s PostProcess graph where attached annotator nodes are placed is evaluated just after render products are ready:
# Inside syntheticdata.py of omni.syntheticdata extension
def post_process_graph_tick_order() -> int:
"""Return the post process graph tick order."""
# eCheckForHydraRenderComplete + 1: after the render products are available
return carb.settings.get_settings().get("/app/updateOrder/checkForHydraRenderComplete") + 1
If you try to get a data from an annotator inside a graph powered by On Physics Step node, you will always get it lagged by at least a frame because at this moment a PostRender graph with GPU Interop: Render Product Entry node (which gives rendered frames on GPU for an annotator) for your render product has not been evaluated for the current simulation step yet.
- The simulation time by default is ahead of the playback time by 1-2 frame because the
isaacsim.core.simulation_manager.SimulationManger.initialize_physicsmethod which is called when its warmup is needed (usually duringisaacsim.core.api.world.World.reset()call or a simulation reset) does two simulation steps (the second step in_create_simulation_view, see comment 2):
# Inside simulation_manager.py of isaacsim.core.simulation_manager extension
@classmethod
def initialize_physics(cls) -> None:
if SimulationManager._warmup_needed:
...
SimulationManager._physx_interface.update_simulation(SimulationManager.get_physics_dt(), 0.0)
...
# The second step in _create_simulation_view, see post 2
Moreover, when you stop a simulation in an app with GUI, the playback time is reseted to startTimeCode of a root layer (usually it is 0). The simulation time is reseted to 0th frame, and then on the timeline play eventinitialize_physics is performed what moves simulation two frames more forward:
# Inside simulation_manager.py of isaacsim.core.simulation_manager extension
def _warm_start(event) -> None:
if SimulationManager._carb_settings.get_as_bool("/app/player/playSimulations"):
SimulationManager.initialize_physics()
def _on_stop(event) -> None:
SimulationManager._warmup_needed = True
...
@classmethod
def _setup_warm_start_callback(cls) -> None:
if cls._callbacks_enabled["warm_start"] and cls._warm_start_callback is None:
cls._warm_start_callback = cls._timeline.get_timeline_event_stream().create_subscription_to_pop_by_type(
int(omni.timeline.TimelineEventType.PLAY), cls._warm_start
)
@classmethod
def _setup_on_stop_callback(cls) -> None:
if cls._callbacks_enabled["on_stop"] and cls._on_stop_callback is None:
cls._on_stop_callback = cls._timeline.get_timeline_event_stream().create_subscription_to_pop_by_type(
int(omni.timeline.TimelineEventType.STOP), cls._on_stop
)
Now there is 2 frame desynchonization between the main timeline and the simulation, and therefore between the rendering and the simulation too.
I wrote a demo that shows it, here is a typical output for a stage with startTimeCode set to 0:
-------Before World.reset-------
Timeline time: 0.0
Simulation time: 0.0
Render time: 0.0
Going to World.reset
-------TIMELINE PLAY-------
Timeline time: 0.0
Simulation time: 0.03333333507180214
Render time: 0.0
-------CURRENT_TIME_TICKED-------
Timeline time: 0.01666666753590107
Simulation time: 0.03333333507180214
Render time: 0.0
Resetted
-------After World.reset-------
Timeline time: 0.01666666753590107
Simulation time: 0.03333333507180214
Render time: 0.01666666753590107
Going to step 0
-------CURRENT_TIME_TICKED-------
Timeline time: 0.03333333507180214
Simulation time: 0.03333333507180214
Render time: 0.01666666753590107
-------POST_PHYSICS_STEP-------
Timeline time: 0.03333333507180214
Simulation time: 0.05000000260770321
Render time: 0.01666666753590107
Stepped 0. All graphs including the PostRender and PostProcess ones have been evaluated
----------------STEP 0----------------
Timeline time: 0.03333333507180214
Simulation time: 0.05000000260770321
Render time: 0.03333333507180214
Going to step 1
-------CURRENT_TIME_TICKED-------
Timeline time: 0.05000000260770321
Simulation time: 0.05000000260770321
Render time: 0.03333333507180214
-------POST_PHYSICS_STEP-------
Timeline time: 0.05000000260770321
Simulation time: 0.06666667014360428
Render time: 0.03333333507180214
Stepped 1. All graphs including the PostRender and PostProcess ones have been evaluated
----------------STEP 1----------------
Timeline time: 0.05000000260770321
Simulation time: 0.06666667014360428
Render time: 0.05000000260770321
Now stop the playback in GUI and start it again
-------TIMELINE STOP-------
Timeline time: 0.0
Simulation time: 0.06666667014360428
Render time: 0.05000000260770321
-------TIMELINE PLAY-------
Timeline time: 0.0
Simulation time: 0.03333333507180214
Render time: 0.0
-------CURRENT_TIME_TICKED-------
Timeline time: 0.01666666753590107
Simulation time: 0.03333333507180214
Render time: 0.0
-------POST_PHYSICS_STEP-------
Timeline time: 0.01666666753590107
Simulation time: 0.05000000260770321
Render time: 0.0 # will be 0.01666666753590107 at the end of the kit's update cycle
Steps to Reproduce
-
Create a stage in Isaac Sim 5.0.0 with a camera prim at the path “/World/Camera”
-
Download my demo script txt file, remove .txt in the filename and inside change the stage path to yours:
...
# Open a USD Stage with a camera prim on the path /World/Camera
omni.usd.get_context().open_stage(your_stage_path)
...
- Being in a console, run it by python.bat/python.sh like any other standalone python scripts.
- When the playback has been paused, stop it and play again for a few frames.
- See time output logs in the console.
Additional Information
What I’ve Tried
- Set
startTimeCodeof a stage to 1. There is still a small desync that will be accumulated during a simulation:
----------------STEP 0----------------
Timeline time: 0.0500000017384688
Simulation time: 0.05000000260770321
Render time: 0.0500000017384688
- Set physics_dt for
initialize_physicsto 0.0:
# Inside simulation_manager.py of isaacsim.core.simulation_manager extension
@classmethod
def initialize_physics(cls) -> None:
...
SimulationManager._physx_interface.update_simulation(0.0, 0.0)
...
It perfectly synchronizes the time at a startup, but I’m not sure if it doesn’t break a simulation overall:
----------------STEP 0----------------
Timeline time: 0.03333333507180214
Simulation time: 0.03333333507180214
Render time: 0.03333333507180214
They both don’t fix the problem with GUI simulation reset though.
test_timeline_vs_simulaiton.py.txt (2.9 KB)


