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?