Hello. My question is: How do the physics calculation step and the rendering step relate to real time? Examples such as time_stepping.py from standalone_example/api/omni.isaac.core, contain the following code:
simulation_context.set_simulation_dt(physics_dt=1.0 / 60.0, rendering_dt=1.0 / 600.0)
for step in range(10):
simulation_context.step(render=True)
We will see that for one call to the step_callback function, there are 10 calls to the render_callback function. If in the render_callback function we will put timestamps:
import time
def render_callback(event):
print("update app with step: ", time.time())
we will see that the actual frequency of calling the render_callback function does not correspond to 60 Hz.
How do I organize the main loop in which simulation_context.step is called to provide a time close to real time? I need to be able to, for example, publish ROS messages with a certain frequency, etc.
When running a standalone example with SimulationApp, Isaac sim will run as fast as possible.
Your options are:
publish a ROS Clock message and use that as your time so things stay in sync"
use time.sleep between each step call to get it to run at a slower rate. This works if your simulation is running faster than realtime
one example of the latter: (The SteadyRate class is copied from omni.isaac.cortex tools.py)
class SteadyRate:
""" Maintains the steady cycle rate provided on initialization by adaptively sleeping an amount
of time to make up the remaining cycle time after work is done.
Usage:
rate = SteadyRate(rate_hz=30.)
while True:
do.work() # Do any work.
rate.sleep() # Sleep for the remaining cycle time.
"""
def __init__(self, rate_hz):
self.rate_hz = rate_hz
self.dt = 1.0 / rate_hz
self.last_sleep_end = time.time()
def sleep(self):
work_elapse = time.time() - self.last_sleep_end
sleep_time = self.dt - work_elapse
if sleep_time > 0.0:
time.sleep(sleep_time)
self.last_sleep_end = time.time()
rate = SteadyRate(60)
simulation_context.set_simulation_dt(physics_dt=1.0 / 60.0, rendering_dt=1.0 / 600.0)
for step in range(10):
simulation_context.step(render=True)
rate.sleep()
Hello, @Hammad_M. Thank you so much for your reply. I have a few comments:
When using the ROS Clock block in the model, the time in the other nodes will be synchronized with the time of the model. And it works fine if I don’t have to enter any data from physical devices. For example, I has implemented a car model in Isaac Sim, which works 3 times faster than real time, and I want to control it using the game steering wheel. It means that I will have to drive three times more actively.
I can write the main application loop myself, as you suggest to do, however, I would prefer to run the model from the main Isaac Sim window and have a parameter “Real-time simulation enabled” as for example it is done in CoppeliaSim, for real-time emulation.
Most of our examples use the IsaacReadSimulationTime node for publishing data.
There is also a IsaacReadSystemTime OmniGraph node that can be used as a drop in replacement
Hello. I updated Isaac Sim to version 2022.2.0. I found that when running the example (Isaac Examples→ROS→Navigation), the frequency of data publication floats (30 Hz → 60 Hz and vice versa). A message of the rosgraph_msgs/Clock type is published in the model. In the previous version of Isaac Sim, when running the same example and setting the /use_sim_time parameter to true, data from the model was published with a frequency of 60 Hz (the Time Steps Per Second parameter is 60). And this frequency was maintained very accurately. Question: what happened and how to synchronize now?
I’m sorry. Everything is described in the manual: Physics Core — Omniverse Code documentation. I have to set Use Fixed Time Stepping in Rendering Properties and change value Simulation Frame Rate in Physics Settings.