Speed up the simulation without affecting the physics

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??

1 Like

Hi,

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.

/isaac-sim/_build/linux-x86_64/release/exts/omni.isaac.synthetic_utils/omni/isaac/synthetic_utils/scripts/omnikit.py

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)