How to speed up simulation in Isaac-Sim

Hello!

I have attached a simple script for a franka pushing a cube. I wanted to speed up the simulation by changing the physics step size and min_simulation_frame_rate. However, there is no change in the speed of the simulation.

In addition, I am not quite sure whether stepping is using gpu or not. When I enable gpu dynamics from physics scene in the gui, the simulation gets slower.

Here is the code and runtime information.

from omni.isaac.kit import SimulationApp
simulation_app = SimulationApp({"headless": False}) 

from omni.isaac.core import World
from omni.isaac.core.objects import DynamicCuboid
from omni.isaac.franka import Franka
from omni.isaac.franka import KinematicsSolver
import numpy as np


world = World()
world.scene.add_default_ground_plane()
franka = world.scene.add(Franka(prim_path="/World/Fancy_Franka", name="fancy_franka"))
world.reset()
fancy_cube =  world.scene.add(DynamicCuboid(
        prim_path="/World/random_cube",
        name="fancy_cube",
        position=np.array([0.1, 0.6, 0.1]),
        scale=np.array([0.5, 0.5, 0.5]),
        color=np.array([0, 0, 1.0]),
    ))


solver = KinematicsSolver(franka)

current_joint_positions = franka.get_joint_positions()

cube_position,_ = fancy_cube.get_world_pose()


goal_config = solver.compute_inverse_kinematics(cube_position)[0]
joint_positions = goal_config.joint_positions


steps = 2000

a1 = np.linspace(current_joint_positions[0],joint_positions[0],steps)
a2 = np.linspace(current_joint_positions[1],joint_positions[1],steps)
a3 = np.linspace(current_joint_positions[2],joint_positions[2],steps)
a4 = np.linspace(current_joint_positions[3],joint_positions[3],steps)
a5 = np.linspace(current_joint_positions[4],joint_positions[4],steps)
a6 = np.linspace(current_joint_positions[5],joint_positions[5],steps)
a7 = np.linspace(current_joint_positions[6],joint_positions[6],steps)


for i in range(steps):
    goal = np.array([a1[i],a2[i],a3[i],a4[i],a5[i],a6[i],a7[i],joint_positions[7],joint_positions[8]])
    goal_config.joint_positions = goal
    franka.apply_action(goal_config)
    world.step(render = True) 

world.reset()
    
simulation_app.close() 

I would be grateful if you could give me any hints on how to speed up the simulation without affecting the physics. Thank you!

Hi @hailegashaw12 - the speed of the simulation is primarily determined by the physics step size and the minimum simulation frame rate. However, these settings can be influenced by other factors such as the complexity of the scene, the number of physics objects, and the computational resources available.

Here are some suggestions to speed up your simulation:

  1. Physics Step Size: The physics step size determines the time interval for each physics simulation step. A smaller step size will result in a more accurate simulation but will also require more computational resources and thus slow down the simulation. Conversely, a larger step size will speed up the simulation but may result in less accurate physics. You can adjust the physics step size in your script using the world.set_physics_step_size(step_size) function, where step_size is the desired step size in seconds.
  2. Minimum Simulation Frame Rate: The minimum simulation frame rate determines the minimum number of physics simulation steps per second. If the actual frame rate drops below this value, the simulation will slow down to maintain the accuracy of the physics. You can adjust the minimum simulation frame rate in your script using the world.set_min_simulation_frame_rate(frame_rate) function, where frame_rate is the desired frame rate in frames per second.
  3. GPU Dynamics: Enabling GPU dynamics can potentially speed up the simulation by offloading the physics calculations to the GPU. However, this will only be beneficial if your GPU is powerful enough and not already fully utilized by other tasks. If enabling GPU dynamics slows down the simulation, it may be that your GPU is not able to handle the additional load. You can enable or disable GPU dynamics in your script using the world.set_gpu_dynamics_enabled(enabled) function, where enabled is a boolean value indicating whether GPU dynamics should be enabled.
  4. Optimize the Scene: As mentioned in the previous response, optimizing the scene can also help to speed up the simulation. This includes reducing the complexity of the scene, implementing level of detail (LOD), culling invisible objects, and optimizing the physics settings.
2 Likes

@rthaker just wondering about the GPU dynamics piece … I’ve experimented with various simulation parameters (use_gpu_pipeline, use_flatcache, use_gpu, …) and tried other tricks (like overwriting the omni.physx GPU setting and increasing the thread count), but my code still runs slower on GPU than CPU.

I’m confused because, according to nvidia-smi, my GPU (at ~70% usage) technically has greater remaining capacity than my CPU cores (often maxing out at 100%). My intuition says that GPU should be running faster; are there any other settings I should toggle or possible sources of slowness that I haven’t yet looked into?

Additionally, is there a set_min_simulation_frame_rate (or similar) method for World? I haven’t been able to find this setting in the source code of at least Isaac Sim version 2022.2.1

Thank you for your swift reply, @rthaker.

My workstation spec:
GPU - GeForce RTX 3080
CPU - Intel(R) Xeon(R) W-2295 CPU @ 3.00GHz

My scene is a very simple scenario with one robot and a cube object. As @bubblefish said, I also think GPU should be running faster.

Additional experiment:

With 100 parallel robots with single object each → the simulation speed is same with or without gpu dynamics enabled.

With less than 10 robots → enabling gpu dynamics made simulation slower.

At this point, it seems that enabling gpu dynamics is no use. I don’t think this could be the case and may be I am doing something wrong. Kindly, are there any other settings to look into?

Hello - Basically GPU simulation becomes faster only for larger environments. With smaller simulation size, there is a fixed cost for the GPU simulation.

If you have one Franka then most likely CPU will be the fastest, maybe even a single threaded (set num threads for physics to 0) would be the fastest.

1 Like

@rthaker how do you set up occlusion culling on Isaac sim? thanks

Hi @felipe.cunha1 - Occlusion culling is a rendering optimization technique that improves performance by not rendering objects that are occluded by other objects. However, as of the current version of Isaac Sim, there is no explicit setting or feature to enable occlusion culling.

1 Like

I did not find these method for World as well? could you share where to find the method?

World don’t have these methods.

2 Likes

I didn’t find these function names and interfaces in version 2023, can you guide me how to set them up in the latest version?

1 Like

Hello,

I’m curious to know if the culling of invisible objects is working in the latest version of Isaac Sim. I have a landscape scene with lots of trees, and the FPS is really slow.

Do you have any tutorials on how I can optimize my scene by using LOD and culling invisible objects? Any tips or advice to improve performance would be greatly appreciated!

Thanks in advance!