Basically I am looking for the parameter which is equivalent to Unity’s “time scale”, the parameter that I can speed up the simulation without affecting the physics. I know I can make the simulation faster by changing the time step bigger (“update per second” smaller), but that will actually make the simulation unstable (etc. unstable collision detection).
Is there any way to execute more step in the simulation in short time without making the physics worse??
According to the docstrings of the update method (line 170 of /isaac-sim/_build/linux-x86_64/release/exts/omni.isaac.synthetic_utils/omni/isaac/synthetic_utils/scripts/omnikit.py) you can decouple the physics step size from rendering using the /physics/timeStepsPerSecond and /physics/maxNumSteps parameters.
def update(self, dt=0.0, physics_dt=None, physics_substeps=None):
"""Render one frame. Optionally specify dt in seconds, specify None to use wallclock.
Specify physics_dt and physics_substeps to decouple the physics step size from rendering
For example: to render with a dt of 1/30 and simulate physics at 1/120 use:
- dt = 1/30.0
- physics_dt = 1/120.0
- physics_substeps = 4
Args:
dt (float): The step size used for the overall update, set to None to use wallclock
physics_dt (float, optional): If specified use this value for physics step
physics_substeps (int, optional): Maximum number of physics substeps to perform
"""
# dont update if exit was called
if self._exiting:
return
if physics_substeps is not None and physics_substeps > 0:
self.kit_settings.set("/physics/maxNumSteps", int(physics_substeps))
if dt is not None:
if self.kit_settings and dt > 0.0:
if physics_dt is None or physics_dt <= 0.0:
self.kit_settings.set("/physics/timeStepsPerSecond", float(1.0 / dt))
else:
self.kit_settings.set("/physics/timeStepsPerSecond", float(1.0 / physics_dt))
self.app.update(dt)
else:
time_now = time.time()
dt = time_now - self.last_update_t
self.last_update_t = time_now
if self.kit_settings and dt > 0.0:
if physics_dt is None or physics_dt <= 0.0:
self.kit_settings.set("/physics/timeStepsPerSecond", float(1.0 / dt))
else:
self.kit_settings.set("/physics/timeStepsPerSecond", float(1.0 / physics_dt))
self.app.update(dt)
Also, you can configure your simulation in the Simulator section from the Physics > Settings window.
The parameter "/physics/timeStepsPerSecond" tells the simulator what is the physics time stepping.
Isaac sim is set to run real-time, and automatically compute how many simulation steps to run per rendering, constrained by the Max num steps (/physics/maxNumSteps) setting.
Below is a script to force execute physics time-steps decoupled from rendering or timeline buttons. Bear in mind that the stepping loop is a locking function, and UI will freeze for the duration of the loop. There is a known bug currently being worked on on this approach where the simulation may freeze if a contact report happens during one of the steps.
from pxr import Usd, UsdGeom
import omni.usd
from omni.physx import acquire_physx_interface
stage = omni.usd.get_context().get_stage()
print(stage)
physx = acquire_physx_interface()
dt = 1/60.0
physx.reset_simulation()
physx.start_simulation()
# Simulate 20 steps, increase start_time if the desired initial step time is not at zero
start_time = 0.0
for i in range(20):
physx.update_simulation(dt, start_time+ i*dt)
physx.update_transformations(False, True)
# To stop the simulation and reset the scene:
def stop():
physx.reset_simulation()
physx.update_transformations(False, True)
Thanks for the reply. I have tried changing the /physics/timeStepsPerSecond but it seems to only change the frame rate that physics updates instead of how fast the system runs. Is there a way to make isaac sim runs faster/slower than realtime?
Yes – Using the script in the previous reply should show you how to step the physics scene decoupled from rendering,
The only issue in using this script with the released version is if you have any object with the ContactReportAPI enabled, it will freeze the simulation. This issue has already been fixed for upcoming releases.
thanks, I have been trying your script in extension, but it does not seem to work. To be specific, currently, I am running a robotics application as an extension using isaac-sim, but we want to be able to test it at a faster speed. I am able to make the simulation run slower by changing the /physics/timeStepsPerSecond and `/physics/maxNumSteps, but there is no minNumSteps. I think the better question is how to adjust how many simulation steps per rendering when running an extension?
How are you trying to run the script? What is the error you are getting? A video or some other sort of information to help us understand what’s happening would greatly assist us to provide you with the correct next steps.
You may want to decouple physics from rendering on your extension, and on the editor update callback, call the equivalent of:
for i in range(n_steps):
physx.update_simulation(dt, start_time+ i*dt)
physx.update_transformations(False, True)
for as many time-steps as you want to perform on each rendering. Make sure to not click on the UI Play if you are updating the physics with your own steps, as it would recapture the physics scene and you’d need to reload the stage to be able to control through with the scripted update.
as a side note: Please be sure that the settings in the physics panel are as such:
I have the same issue and was still confused.
What I have done now is use:
while kit.app.is_running():
kit.update(1.0, 1.0 / 60.0)
This seems to run everything very quickly while still simulating physics reasonably accurately. But I don’t understand it. Now the physics is updated using dt = 1/60, while the overall system is updated with a dt = 1 second i.e. is rendering immediately what has happened 1 second into the future? Is that right?
What I really want is a deterministic simulation time update i.e. run the simulation at 10xwallClockTime. How do I do this?
if you want to run the simulation at precisely 10x wall Clock time, you’d need some sort of timed loop (e.g it enters the loop every 1/600s)
This can only be achieved if the full simulation takes less time to solve than sim_step/10 (i.e. you can simulate a physics step ten times faster than the period simulated - For a simulation running on 1/60s you’d need the physics step to be simulated at most at 1/600s)
assuming you are able to run your simulation at 1/(10*60)s, you’d need your loop to be something like this
period = 1/600.0
while True:
start_time = time.time()
do_stuff() # a function where you call the physx update simulation and everything you need to do
end_time = time.time()
threading.sleep(period - (end_time -start_time)) # Sleep this loop for the period minus the time it took to execute the code
Bear in mind that Ubuntu is not an RTOS, so it will sleep the thread for the requested time at best effort (it will try to stay on time, but no guarantees it will sleep precisely for the given time requested)
Hi @rgasoto , Could you provide some insight/commentary on the difference between the solution specified in this post Get simulation time - #2 by Hammad_M and the approach you offer here? For example, what are the differences in physics calculations with the two methods, does one approach have better control over ensuring stable physics?
As an example case for collisions, would reducing the timestep with one method or the other change the collision dynamics.
Hi!
It’s essentially the same method, one being called through the Isaac sim UI, the other directly through the code API.
The choice of time steps per second does have an impact on the simulation stability, as it allows for more iterations between collisions and more accurately capturing objects interpenetration and their resulting repulsion forces, therefore having a more precise impulse response. For example, if you have a small object running at a high speed, in order to capture its collision against some other object (let’s say equally small), you would need a sufficiently small time step to capture when the objects collide, instead of just passing through one another.
Hi @rgasoto , sorry I wasn’t clear. I was referring to the code examples (not the UI part). Like the difference between the step and update_simulation methods.
But assuming all the methods calling an update are the same, I am wondering if there are other settings that are impacted. I know the simulation accuracy should be ‘better’ with smaller timesteps, but are all settings scaled as well? For example (but not limited to), “sleep threshold” or “elasticity damping”.
I would like to try the scripts provided, but I don’t know where to put this python script, so that it gets executed. Until now I have only been using the “Action Graph Editor”.
Thanks in advance
Hi @rgasoto, I’m trying to implement your way to step physics independently from rendering, but I’m not able to make it work. Indeed the physics stepping is still following the dt indicated by the variable timeStepsPerSecond of the physicsScene and not the one given to update_simulation function. My loop is as follows.
dt = 1.0 / 400.0
count = 0
time = 0.0
while self._sim_app.is_running():
self._physx.update_simulation(dt, time)
self._physx.update_transformations(False, True)
count = count + 1
time = time + dt
if count == 40 :
self._world.render()
count = 0
Hi @paros97 - The update_simulation function in the omni.physx module is used to step the physics simulation by a certain amount of time. The timeStepsPerSecond parameter in the physics scene determines the fixed time step used by the physics simulation, but it does not control the actual simulation time. The simulation time is controlled by the dt argument passed to update_simulation.
In your code, you’re correctly calling update_simulation with a dt of 1.0 / 400.0, which should step the simulation by 1/400th of a second each time it’s called. However, you’re also calling update_transformations immediately after update_simulation, which updates the transformations of all physics actors to match the current simulation state. This could be causing the physics simulation to appear as if it’s stepping at the same rate as the rendering.
To step the physics simulation independently from the rendering, you should only call update_transformations when you’re ready to render a new frame. In your case, this would be inside the if count == 40 block. Here’s how you could modify your code:
dt = 1.0 / 400.0
count = 0
time = 0.0
while self._sim_app.is_running():
self._physx.update_simulation(dt, time)
count = count + 1
time = time + dt
if count == 40:
self._physx.update_transformations(False, True)
self._world.render()
count = 0
This way, the physics simulation will be stepped 40 times for each rendered frame, effectively running the physics simulation at a higher rate than the rendering.
So if I understood correctly, dt can be timeStepsPerSecond or one of its multiples, right?
Moving the update_transform function does improve the real-time factor. However I need to publish some transforms via ROS at each physics step, that’s why previously I put update_transform after update_simulation.
I did some experiments and I discovered that one transform is updated at each physics step even without update_transform. It is the transform from world Xform to the one which contains an imu sensor. Instead, all the other transforms are not updated. Do you know the reason why that transform is still being updated? Can I extend this behavior to the other Xforms which need to be published at each physics step?
So if I understood correctly, dt can be timeStepsPerSecond or one of its multiples, right?
dt is 1/timeStepsPerSecond, so if you have 60 timesteps per second, your dt would be 0.016667.
The physics objects get automatically updated without update_transform when querying them. but any frame that is not directly bound to a physics rigid body needs the additional evaluation step. This is done due to performance reasons to maintain optimal perf. Since you need these additional frame of references, I’d move the updateTransformations to calc at every step with physics.
So there is no way to speed up the simulation if I need to update the transform of a few frames at each physics step? I’m running Isaac Sim on an RTX4090 and its load is only 50% during the simulation.
Can someone help me to find out where Physics > Settings window in the latest Isaac Sim 2023.1 version?
Was Physics > Settings window deprecated in the current version? Whether timeStepsPerSecond and maxNumSteps were merged into other setting item?