Aligning physics stepping with real time?

Hello - I have been using Isaac Sim for few months for simulated teleoperation through ROS2 with haptic feedback. For this I would like to maintain a stable ~200 Hz publishing rate for the publishing and subscribing of the robot joint states. For my controller I am using an Action Graph with a On Physics Step trigger. This is because my machine is not capable of rendering full frames at the desired frequency however every physics step can run extremely quickly at sub ms rates. After scouring the NVIDIA forums it seems the most pertinent parameters for timestepping are numPhysicsSteps and a large number of frame rate parameters. I have set numPhysicsSteps=200 and minFrameRate=1 as stable graphics rendering is secondary to my goal. With these settings I am able to achieve stable frame-rates of 60-100Hz however the time-stepping is extremely inconsistent. In particular I notice that the time between physics steps varies from 0.5-20ms which is unmanageable for a real time haptic controller. I am trying to avoid these latency spikes and make sure that physics steps always run every ~5ms. I have tried getting this to work in extension mode and standalone mode using the asyncio library to no avail. It seems I have tried every combination of settings and still cannot get this to work. Moreover I have tried to set FixedTimeStepping to False to at least get the physics stepping aligned with real time and still get constant physics steps. Playing around with AsyncRendering and AsynchronousPhysics also seem to have negligible effect on this. I have included an image of the timing of my physics loop where you can see sudden latency spikes and general instability. I have also included an image of some of the settings I have been playing with in my custom extension. I am working with Isaac Sim 4.5 on Ubuntu 22. My machine has an Ada 4000 GPU with an 13th Gen Intel i9 processor.

I have struggled with this for a couple months now and would appreciate any help with this issue from the community or developers. I understand this is an unorthodox request and hope that this desired behavior is even achievable with Isaac Sim. Thank you!

1 Like

Have you tried simplifying the scene to see if the inconsistency is related to the physics engine under load?

These measurements are for the scene in initial conditions (nothing is moving), so I don’t know why this would have an effect. I am wondering if there is any way to decouple the graphics and physics loops and have physics run on a high priority thread. To the best of my ability I have tried implementing this as a standalone script using asyncio and am getting some improvements. I am not that familiar with using asyncio so I am looking for suggestions or improvements. Again, my main goal is to get physics steps more or less consistent with real world time (~5ms).

import argparse
import asyncio
import sys
import time
from isaacsim import SimulationApp
import rclpy

# Simulation configuration
CONFIG = {
    "width": 1280,
    "height": 720,
    "sync_loads": True,
    "headless": False,
    "renderer": "RaytracedLighting",
    #"extra_args": ["--/app/useFabricSceneDelegate=1"]
}
PHYSICS_DT = 1/200.  # 200 Hz

# Command-line arguments
parser = argparse.ArgumentParser("USD Loader")
parser.add_argument("--usd_path", type=str, required=True)
parser.add_argument("--headless", action="store_true", default=False)
parser.add_argument("--test", action="store_true", default=False)
args, unknown = parser.parse_known_args()

CONFIG["headless"] = args.headless
simulation_app = SimulationApp(launch_config=CONFIG)

import carb
import omni
from isaacsim.storage.native import is_file
from isaacsim.core.utils.stage import is_stage_loading
#from isaacsim.core.api import SimulationContext
from isaacsim.core.api import World
import omni.graph.core as og


# Load USD stage
if not is_file(args.usd_path):
    carb.log_error(f"USD path invalid: {args.usd_path}")
    simulation_app.close()
    sys.exit()

carb.settings.get_settings().set_bool("/app/asyncRendering", True)
carb.settings.get_settings().set_bool("/app/player/useFixedTimeStepping", False)
carb.settings.get_settings().set_bool("/physics/updateToUsd", False)
carb.settings.get_settings().set_bool("/physics/updateVelocitiesToUsd", False)

omni.usd.get_context().open_stage(args.usd_path)
simulation_app.update()
simulation_app.update()

print("Loading stage...")
while is_stage_loading():
    simulation_app.update()
print("Loading Complete")
omni.timeline.get_timeline_interface().play()

# Simulation context setup
world = World(physics_dt=PHYSICS_DT)
world.initialize_physics()
world.play()

async def physics_loop():
    next_step = asyncio.get_event_loop().time()
    last_physics_time = time.perf_counter()
    while simulation_app.is_running():
        this_physics_time = time.perf_counter()
        print("dt_physics: ", this_physics_time - last_physics_time)
        last_physics_time = this_physics_time
        world.step(render=False)
        next_step += PHYSICS_DT
        await asyncio.sleep(max(0, next_step - asyncio.get_event_loop().time()))

async def render_loop():
    last_graphics_time = time.perf_counter()
    while simulation_app.is_running():
        # this_graphics_time = time.perf_counter()
        # print("dt_graphics: ", this_graphics_time - last_graphics_time )
        # last_graphics_time = this_graphics_time
        await world.render_async()  # explicitly render asynchronously
        await asyncio.sleep(0.)  # limit to ~60Hz

async def main():
    physics = asyncio.create_task(physics_loop())
    render = asyncio.create_task(render_loop())
    await asyncio.gather(physics, render)

simulation_app.run_coroutine(main(), run_until_complete=False)

while simulation_app.is_running():
    simulation_app.update()

world.stop()
simulation_app.close()