New clocking/ticking system issues

Hey,
I’m quite confused by the new clocking system/its relation with the timeline.

First of all the two

omni.kit.commands.execute("RosBridgeUseSimTime", use_sim_time=True)
omni.kit.commands.execute("RosBridgeUsePhysicsStepSimTime", use_physics_step_sim_time=True)

Are nowhere to be found. Especially the second one.

Let’s consider only the case in which I want to publish the clock message.
I set

  • physics_dt = 1/240

timeline auto update = True

Snippet #1

while True:
            og.Controller.set(og.Controller.attribute("/ClockActionGraph/OnImpulseEvent.state:enableImpulse"), True)
            simulation_context.render()

clock message gets published with the same time at 240 Hz (not stepping physics so this is good), time however, is advancing (as expected, so auto update will be disabled later to have more control)

Snippet #2

while True:
            og.Controller.set(og.Controller.attribute("/ClockActionGraph/OnImpulseEvent.state:enableImpulse"), True)
            simulation_context.step()

I get the correct clock time and the correct rate of the message independently of the rendering_dt while timeline is correctly advancing.

Snippet #3

while True:
            og.Controller.set(og.Controller.attribute("/ClockActionGraph/OnImpulseEvent.state:enableImpulse"), True)
            simulation_context.step(render=False)

Nothing is being published.

Assuming clock is advancing with physics and messages published with render I tried this based on the previous one.
Snippet #4

while True:
            og.Controller.set(og.Controller.attribute("/ClockActionGraph/OnImpulseEvent.state:enableImpulse"), True)
            for _ in range(1000):
                simulation_context.step(render=False)
            simulation_context.render()

Clock is published at 0.240 Hz with time that are 1000*1/240 s aparts while timeline proceed based on render

Therefore, I can extrapolate from this that the physics step bring my “clock” forward, while render publish it, and the timeline frame is based on the rendering calls.

If I disable timeline auto update, weird things happens
Snippet #1 Same behaviour

Snippet #2 WEIRD clock is being published, “correct” hz (cannot verify) TIME IS STUCK (e.g. always clock: secs: 0 nsecs: 550000029 )

Snippet #3 clearly Nothing is being published

Snippet #4: Clock is published at 0.240 Hz with time that are 1000*1/240 s aparts while timeline is stuck (as expected)

So I came up with Snippet #5:

while True:
            og.Controller.set(og.Controller.attribute("/ClockActionGraph/OnImpulseEvent.state:enableImpulse"), True)
            simulation_context.step(render=False)
            simulation_context.step()

And here clock is advancing with the right step and publishing at the right rate. NOTE: I am NOT moving the timeline. Again weird: clock should be advancing twice as fast (physics is called twice).

This is kinda confusing.

  • Why Snippet#2 does not work while #5 yes in the second set of experiments?
  • How can I publish when render=False? so at physics step? In that way I can render only when I need pictures and not when I need my Clock. In 2021.2.1 was easy, now it is not working anymore.
  • Related (see this) how can I manually step ros cameras? (I want to tick the specific camera, not to get it published every time render is called) Or, alternatively, how can I have rendering “blocking” and internally doing all the subrenders for example during pathtracing?
  • can someone explain what triggers what and what advances what?

A small note, my desire is to be able to render/step physics manually (as yours I guess, since it is a selling point of IsaacSim). And being able to publish what I want when I want and finely control everything (as it was possible with 2021.2.1).

And finally, not having “render” call publishing images to ROS but I want to decide when that happens, unless render becomes blocking and the above physics step/impulse triggering becomes controllable by me/gets triggered by the physics step

@hmazhar

@eliabntt94 thanks for the detailed breakdown, snippet three is a scenario that we overlooked.

The simplest way to workaround the issue is to pump a graph manually after updating physics. Or if you want you can pump a graph inside of a physics step callback
og.Controller.evaluate_sync(...)
see
standalone_examples/api/omni.isaac.quadruped/go1_ros1_standalone.py

for an example of how to do this, we publish the clock message at the physics rate from the physics callback

Graphs not getting called in a non-render step is something that we need to fix or find a better workaround for. I’ll file a bug as that is an unintended regression.

Hi @Hammad_M, thanks for your suggestion. I think the point should be as follows

  • clock advancing either with render OR physics (although physics is better being a robotic SIM)
  • graph being triggered whenever we want it triggered. Eg. The old tick component. Rather than being linked to a step (be that render or physics). Maybe just a “simulation_context.trigger_graphs(None => all, [names] only selected)” or something similar. It’ll make everything more controllable

Idk what you mean by pump a graph. I’ll be able to look over it during the weekend since I “left” my job for an internship.

Hi @ltorabi and @Hammad_M.
I’m still having difficulties achieving this with the latest version of IsaacSim you’ve released.
Specifically, I am not able to use
timeline.set_auto_update(False)
has something changed?

everything else seems to work (manually pushing the clock graph). Although I want to suggest to bring back a flag as in the 2021 version :) much easier

@eliabntt94 can you elaborate? do you get an error when calling timeline.set_auto_update(False)?
or is there a specific behavior that changed

No error.
It used to work like this:

  1. Set that to false
  2. Play
  3. Render
    Result: timeline not advancing

This allowed fine control and the advancement of the timeline using forward_one_frame when desired.

Now the result is that the time in the timeline still advances irrespective if the use_sim_time is set to true or false. So if i want to keep physics and everything else while controlling the simulation time (since one render call is not sufficient to have a complete rendering for complex scenes and path tracing) I need to save the time at every loop and manually reset it.

this is the same issue The timeline set_auto_update(False) no longer works

In short, with the previous interface, when auto_update was false and the simulation playing no render/physics call would have advanced the timeline. Now, every render call advances it.

Now, since for complex scenes the render call is shorter than the time necessary to render the environment for RTX and for Path Tracing a render call advances only spp steps over the totalSpp, we still need multiple render calls to have a correct rendered image. This implies that the timeline would advance multiple times, changing the animations and the positions and the deformations of the animated objects of not just one time step.