Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
145 changes: 145 additions & 0 deletions scripts/benchmarks/benchmark_newton_xform_prim_view.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,145 @@
# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Benchmark script for Newton XformPrimView performance.

Tests the performance of batched transform operations using Newton's GPU-backed
XformPrimView (sites / body_q) without requiring Isaac Sim Kit.

Usage:
VIRTUAL_ENV=env_isaaclab ./isaaclab.sh -p scripts/benchmarks/benchmark_newton_xform_prim_view.py --num_envs 4096
VIRTUAL_ENV=env_isaaclab ./isaaclab.sh -p scripts/benchmarks/benchmark_newton_xform_prim_view.py --num_envs 4096 --num_iterations 200
"""

from __future__ import annotations

import argparse
import time

import torch
import warp as wp

from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg
from isaaclab_newton.sim.views import XformPrimView

import isaaclab.sim as sim_utils
from isaaclab.assets import RigidObjectCfg
from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
from isaaclab.sim import SimulationCfg, build_simulation_context
from isaaclab.utils import configclass

NEWTON_SIM_CFG = SimulationCfg(
physics=NewtonCfg(solver_cfg=MJWarpSolverCfg()),
)


@configclass
class BenchSceneCfg(InteractiveSceneCfg):
cube: RigidObjectCfg = RigidObjectCfg(
prim_path="{ENV_REGEX_NS}/Cube",
spawn=sim_utils.CuboidCfg(
size=(0.2, 0.2, 0.2),
rigid_props=sim_utils.RigidBodyPropertiesCfg(),
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
collision_props=sim_utils.CollisionPropertiesCfg(),
),
init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 1.0)),
)


@torch.no_grad()
def benchmark(num_envs: int, num_iterations: int, device: str) -> dict[str, float]:
"""Run the benchmark and return timing results in seconds."""
NEWTON_SIM_CFG.device = device
results: dict[str, float] = {}

with build_simulation_context(device=device, sim_cfg=NEWTON_SIM_CFG, add_ground_plane=True) as sim:
sim._app_control_on_stop_handle = None
scene = InteractiveScene(BenchSceneCfg(num_envs=num_envs, env_spacing=2.0))
sim.reset()

view = XformPrimView("/World/envs/env_.*/Cube", device=device)
print(f" View count: {view.count}")

# -- warmup (compile Warp kernel, first torch allocs) --
for _ in range(5):
view.get_world_poses()

# -- get_world_poses (full) --
torch.cuda.synchronize()
t0 = time.perf_counter()
for _ in range(num_iterations):
pos, quat = view.get_world_poses()
torch.cuda.synchronize()
results["get_world_poses"] = (time.perf_counter() - t0) / num_iterations

# -- get_world_poses (indexed, 50 %) --
half = list(range(0, num_envs, 2))
torch.cuda.synchronize()
t0 = time.perf_counter()
for _ in range(num_iterations):
pos, quat = view.get_world_poses(half)
torch.cuda.synchronize()
results["get_world_poses_indexed_50pct"] = (time.perf_counter() - t0) / num_iterations

# -- set_world_poses (full) --
new_pos = torch.rand((num_envs, 3), device=device)
new_quat = torch.tensor([[0.0, 0.0, 0.0, 1.0]] * num_envs, device=device)
torch.cuda.synchronize()
t0 = time.perf_counter()
for _ in range(num_iterations):
view.set_world_poses(new_pos, new_quat)
torch.cuda.synchronize()
results["set_world_poses"] = (time.perf_counter() - t0) / num_iterations

# -- interleaved set -> get --
torch.cuda.synchronize()
t0 = time.perf_counter()
for _ in range(num_iterations):
view.set_world_poses(new_pos, new_quat)
pos, quat = view.get_world_poses()
torch.cuda.synchronize()
results["interleaved_set_get"] = (time.perf_counter() - t0) / num_iterations

return results


def print_results(results: dict[str, float], num_envs: int, num_iterations: int):
"""Print benchmark results in a formatted table."""
print("\n" + "=" * 70)
print(f"Newton XformPrimView Benchmark: {num_envs} envs, {num_iterations} iters")
print("=" * 70)
print(f"{'Operation':<40} {'Time (ms)':>12} {'us/env':>12}")
print("-" * 70)
for op, t in results.items():
ms = t * 1000
us_per_env = t * 1e6 / num_envs
print(f"{op:<40} {ms:>12.4f} {us_per_env:>12.4f}")
total = sum(results.values()) * 1000
print("-" * 70)
print(f"{'Total':<40} {total:>12.4f}")
print("=" * 70)
print()


def main():
parser = argparse.ArgumentParser(description="Benchmark Newton XformPrimView performance.")
parser.add_argument("--num_envs", type=int, default=4096)
parser.add_argument("--num_iterations", type=int, default=100)
parser.add_argument("--device", type=str, default="cuda:0")
args = parser.parse_args()

print("=" * 70)
print("Newton XformPrimView Benchmark")
print("=" * 70)
print(f" Envs: {args.num_envs} Iterations: {args.num_iterations} Device: {args.device}")
print()

results = benchmark(args.num_envs, args.num_iterations, args.device)
print_results(results, args.num_envs, args.num_iterations)


if __name__ == "__main__":
main()
151 changes: 141 additions & 10 deletions scripts/benchmarks/benchmark_xform_prim_view.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,15 +67,27 @@

import torch

from isaacsim.core.prims import XFormPrim as IsaacSimXformPrimView
from isaacsim.core.utils.extensions import enable_extension
try:
from isaacsim.core.prims import XFormPrim as IsaacSimXformPrimView
from isaacsim.core.utils.extensions import enable_extension

# compare against latest Isaac Sim implementation
enable_extension("isaacsim.core.experimental.prims")
from isaacsim.core.experimental.prims import XformPrim as IsaacSimExperimentalXformPrimView
enable_extension("isaacsim.core.experimental.prims")
from isaacsim.core.experimental.prims import XformPrim as IsaacSimExperimentalXformPrimView

_HAS_ISAACSIM = True
except (ImportError, ModuleNotFoundError):
_HAS_ISAACSIM = False

import isaaclab.sim as sim_utils
from isaaclab.sim.views import XformPrimView as IsaacLabXformPrimView
from isaaclab_physx.sim.views import XformPrimView as IsaacLabFabricXformPrimView

from isaaclab.assets import RigidObjectCfg
from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
from isaaclab.sim import SimulationCfg, build_simulation_context
from isaaclab.utils import configclass
from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg
from isaaclab_newton.sim.views import XformPrimView as IsaacLabNewtonXformPrimView


@torch.no_grad()
Expand Down Expand Up @@ -133,8 +145,10 @@ def benchmark_xform_prim_view( # noqa: C901

# Create view
start_time = time.perf_counter()
if api == "isaaclab-usd" or api == "isaaclab-fabric":
if api == "isaaclab-usd":
xform_view = IsaacLabXformPrimView(pattern, device=args_cli.device, validate_xform_ops=False)
elif api == "isaaclab-fabric":
xform_view = IsaacLabFabricXformPrimView(pattern, device=args_cli.device, validate_xform_ops=False)
elif api == "isaacsim-usd":
xform_view = IsaacSimXformPrimView(pattern, reset_xform_properties=False, usd=True)
elif api == "isaacsim-fabric":
Expand Down Expand Up @@ -279,6 +293,109 @@ def benchmark_xform_prim_view( # noqa: C901
return timing_results, computed_results


@configclass
class _NewtonBenchSceneCfg(InteractiveSceneCfg):
cube: RigidObjectCfg = RigidObjectCfg(
prim_path="{ENV_REGEX_NS}/Object",
spawn=sim_utils.CuboidCfg(
size=(0.2, 0.2, 0.2),
rigid_props=sim_utils.RigidBodyPropertiesCfg(),
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
collision_props=sim_utils.CollisionPropertiesCfg(),
),
init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 1.0)),
)


@torch.no_grad()
def benchmark_newton_xform_prim_view(
num_iterations: int,
) -> tuple[dict[str, float], dict[str, torch.Tensor]]:
"""Benchmark Newton XformPrimView (GPU sites / body_q)."""
timing_results = {}
computed_results = {}

print(" Setting up Newton scene")
newton_sim_cfg = SimulationCfg(device=args_cli.device, physics=NewtonCfg(solver_cfg=MJWarpSolverCfg()))

with build_simulation_context(device=args_cli.device, sim_cfg=newton_sim_cfg, add_ground_plane=True) as sim:
sim._app_control_on_stop_handle = None
scene = InteractiveScene(_NewtonBenchSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0))
sim.reset()

start_time = time.perf_counter()
xform_view = IsaacLabNewtonXformPrimView("/World/envs/env_.*/Object", device=args_cli.device)
timing_results["init"] = time.perf_counter() - start_time

num_prims = xform_view.count
print(f" Newton XformView managing {num_prims} prims")

# warmup
for _ in range(5):
xform_view.get_world_poses()

# get_world_poses
torch.cuda.synchronize()
start_time = time.perf_counter()
for _ in range(num_iterations):
positions, orientations = xform_view.get_world_poses()
torch.cuda.synchronize()
timing_results["get_world_poses"] = (time.perf_counter() - start_time) / num_iterations

computed_results["initial_world_positions"] = positions.clone()
computed_results["initial_world_orientations"] = orientations.clone()

# set_world_poses
new_positions = positions.clone()
new_positions[:, 2] += 0.1
torch.cuda.synchronize()
start_time = time.perf_counter()
for _ in range(num_iterations):
xform_view.set_world_poses(new_positions, orientations)
torch.cuda.synchronize()
timing_results["set_world_poses"] = (time.perf_counter() - start_time) / num_iterations

positions_after, orientations_after = xform_view.get_world_poses()
computed_results["world_positions_after_set"] = positions_after.clone()
computed_results["world_orientations_after_set"] = orientations_after.clone()

# get_local_poses (delegates to world for Newton)
torch.cuda.synchronize()
start_time = time.perf_counter()
for _ in range(num_iterations):
translations, orientations_local = xform_view.get_local_poses()
torch.cuda.synchronize()
timing_results["get_local_poses"] = (time.perf_counter() - start_time) / num_iterations

computed_results["initial_local_translations"] = translations.clone()
computed_results["initial_local_orientations"] = orientations_local.clone()

# set_local_poses
new_translations = translations.clone()
new_translations[:, 2] += 0.1
torch.cuda.synchronize()
start_time = time.perf_counter()
for _ in range(num_iterations):
xform_view.set_local_poses(new_translations, orientations_local)
torch.cuda.synchronize()
timing_results["set_local_poses"] = (time.perf_counter() - start_time) / num_iterations

translations_after, orientations_local_after = xform_view.get_local_poses()
computed_results["local_translations_after_set"] = translations_after.clone()
computed_results["local_orientations_after_set"] = orientations_local_after.clone()

# interleaved set -> get
torch.cuda.synchronize()
start_time = time.perf_counter()
for _ in range(num_iterations):
xform_view.set_world_poses(new_positions, orientations)
positions, orientations = xform_view.get_world_poses()
torch.cuda.synchronize()
timing_results["interleaved_world_set_get"] = (time.perf_counter() - start_time) / num_iterations

return timing_results, computed_results


def compare_results(
results_dict: dict[str, dict[str, torch.Tensor]], tolerance: float = 1e-4
) -> dict[str, dict[str, dict[str, float]]]:
Expand Down Expand Up @@ -566,10 +683,14 @@ def main():
apis_to_test = [
("isaaclab-usd", "Isaac Lab XformPrimView (USD)"),
("isaaclab-fabric", "Isaac Lab XformPrimView (Fabric)"),
("isaacsim-usd", "Isaac Sim XformPrimView (USD)"),
("isaacsim-fabric", "Isaac Sim XformPrimView (Fabric)"),
("isaacsim-exp", "Isaac Sim Experimental XformPrim"),
]
# Uncomment to include Isaac Sim APIs in the comparison (requires isaacsim package):
# if _HAS_ISAACSIM:
# apis_to_test += [
# ("isaacsim-usd", "Isaac Sim XformPrimView (USD)"),
# ("isaacsim-fabric", "Isaac Sim XformPrimView (Fabric)"),
# ("isaacsim-exp", "Isaac Sim Experimental XformPrim"),
# ]

# Benchmark each API
for api_key, api_name in apis_to_test:
Expand All @@ -579,7 +700,6 @@ def main():
profiler = cProfile.Profile()
profiler.enable()

# Cast api_key to Literal type for type checker
timing, computed = benchmark_xform_prim_view(
api=api_key, # type: ignore[arg-type]
num_iterations=args_cli.num_iterations,
Expand All @@ -598,6 +718,17 @@ def main():
print(" Done!")
print()

# Benchmark Newton (separate setup path)
if "cuda" in args_cli.device:
print("Benchmarking Isaac Lab XformPrimView (Newton)...")
timing, computed = benchmark_newton_xform_prim_view(num_iterations=args_cli.num_iterations)
all_timing_results["isaaclab-newton"] = timing
all_computed_results["isaaclab-newton"] = computed
print(" Done!")
print()
else:
print("Note: Skipping Newton benchmark (requires CUDA).\n")

# Print timing results
print_results(all_timing_results, args_cli.num_envs, args_cli.num_iterations)

Expand Down
16 changes: 16 additions & 0 deletions scripts/newton_repro/envs/rough_anymal_d/cloner_info.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
{
"sources": [
"/World/envs/env_0"
],
"destinations": [
"/World/envs/env_{}"
],
"ignore_paths": [
"/World/envs",
"/World/envs/env_0"
],
"up_axis": "Z",
"simplify_meshes": true,
"num_envs": 256,
"env_spacing": 2.5
}
Loading
Loading