Skip to content

Commit 3fca0dc

Browse files
vidurv-nvidiaclaude
andcommitted
Fix SDF config bugs: skip redundant rebuilds, respect hydro patterns, protect non-replicate path
1. _build_sdf_on_mesh: return early when mesh.sdf already exists instead of clearing and rebuilding. Prevents N redundant SDF rebuilds when envs share mesh objects by reference. 2. _create_sdf_collision_from_visual: respect HydroelasticCfg shape_patterns when creating collision shapes from visual meshes. Previously applied hydroelastic unconditionally. 3. instantiate_builder_from_stage: use skip_mesh_approximation=True and selective convex hull approximation (same as newton_replicate path) to preserve triangle meshes needed for SDF. 4. Update test_sdf_config.py: test now expects no-op when SDF already exists on mesh. Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>
1 parent 9b112c7 commit 3fca0dc

File tree

2 files changed

+65
-20
lines changed

2 files changed

+65
-20
lines changed

source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py

Lines changed: 61 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -392,7 +392,7 @@ def _build_sdf_on_mesh(mesh, sdf_cfg, res_overrides, label: str):
392392
if mesh is None:
393393
return
394394
if mesh.sdf is not None:
395-
mesh.clear_sdf()
395+
return # SDF already built (shared by reference from prototype)
396396
resolution = sdf_cfg.max_resolution
397397
if res_overrides is not None:
398398
for pat, res in res_overrides:
@@ -431,18 +431,9 @@ def _create_sdf_collision_from_visual(
431431
if builder.shape_flags[si] & ShapeFlags.COLLIDE_SHAPES and builder.shape_body[si] in matched_bodies:
432432
bodies_with_collision.add(builder.shape_body[si])
433433

434-
shape_cfg_kwargs = dict(
435-
density=0.0,
436-
has_shape_collision=True,
437-
has_particle_collision=True,
438-
is_visible=False,
439-
)
440-
if sdf_cfg.margin is not None:
441-
shape_cfg_kwargs["margin"] = sdf_cfg.margin
442-
if hydro_cfg is not None:
443-
shape_cfg_kwargs["is_hydroelastic"] = True
444-
shape_cfg_kwargs["kh"] = hydro_cfg.k_hydro
445-
sdf_shape_cfg = ModelBuilder.ShapeConfig(**shape_cfg_kwargs)
434+
hydro_patterns = None
435+
if hydro_cfg is not None and hydro_cfg.shape_patterns is not None:
436+
hydro_patterns = [re.compile(p) for p in hydro_cfg.shape_patterns]
446437

447438
num_added = 0
448439
num_hydro = 0
@@ -461,16 +452,35 @@ def _create_sdf_collision_from_visual(
461452
cls._build_sdf_on_mesh(mesh, sdf_cfg, res_overrides, builder.shape_label[visual_si])
462453

463454
body_lbl = builder.body_label[body_idx]
455+
shape_label = f"{body_lbl}/sdf_collision"
456+
457+
# Check if this shape should get hydroelastic (respecting hydro shape_patterns)
458+
apply_hydro = hydro_cfg is not None and (
459+
hydro_patterns is None or any(p.search(shape_label) for p in hydro_patterns)
460+
)
461+
462+
shape_cfg_kwargs = dict(
463+
density=0.0,
464+
has_shape_collision=True,
465+
has_particle_collision=True,
466+
is_visible=False,
467+
)
468+
if sdf_cfg.margin is not None:
469+
shape_cfg_kwargs["margin"] = sdf_cfg.margin
470+
if apply_hydro:
471+
shape_cfg_kwargs["is_hydroelastic"] = True
472+
shape_cfg_kwargs["kh"] = hydro_cfg.k_hydro
473+
464474
builder.add_shape_mesh(
465475
body=body_idx,
466476
xform=builder.shape_transform[visual_si],
467477
mesh=mesh,
468478
scale=builder.shape_scale[visual_si],
469-
cfg=sdf_shape_cfg,
470-
label=f"{body_lbl}/sdf_collision",
479+
cfg=ModelBuilder.ShapeConfig(**shape_cfg_kwargs),
480+
label=shape_label,
471481
)
472482
num_added += 1
473-
if hydro_cfg is not None:
483+
if apply_hydro:
474484
num_hydro += 1
475485

476486
return num_added, num_hydro
@@ -703,14 +713,49 @@ def instantiate_builder_from_stage(cls):
703713
builder.add_usd(stage, ignore_paths=ignore_paths, schema_resolvers=schema_resolvers)
704714

705715
# Build a prototype from the first env (all envs assumed identical)
716+
# Use skip_mesh_approximation + load_visual_shapes to preserve
717+
# triangle meshes needed for SDF (same as newton_replicate path).
706718
_, proto_path = env_paths[0]
707719
proto = ModelBuilder(up_axis=up_axis)
708720
proto.add_usd(
709721
stage,
710722
root_path=proto_path,
723+
load_visual_shapes=True,
724+
skip_mesh_approximation=True,
711725
schema_resolvers=schema_resolvers,
712726
)
713727

728+
# Approximate non-SDF meshes with convex hulls (preserves SDF meshes)
729+
cfg = PhysicsManager._cfg
730+
sdf_cfg = getattr(cfg, "sdf_cfg", None) if cfg is not None else None
731+
body_pats = [re.compile(x) for x in sdf_cfg.body_patterns] if sdf_cfg and sdf_cfg.body_patterns else None
732+
shape_pats = [re.compile(x) for x in sdf_cfg.shape_patterns] if sdf_cfg and sdf_cfg.shape_patterns else None
733+
has_sdf_patterns = body_pats is not None or shape_pats is not None
734+
735+
if has_sdf_patterns:
736+
from newton import GeoType
737+
738+
sdf_bodies: set[int] = set()
739+
if body_pats is not None:
740+
for bi in range(len(proto.body_label)):
741+
if any(pat.search(proto.body_label[bi]) for pat in body_pats):
742+
sdf_bodies.add(bi)
743+
approx_indices = []
744+
for i in range(len(proto.shape_type)):
745+
if proto.shape_type[i] != GeoType.MESH:
746+
continue
747+
if proto.shape_body[i] in sdf_bodies:
748+
continue
749+
if shape_pats is not None:
750+
lbl = proto.shape_label[i] if i < len(proto.shape_label) else ""
751+
if any(pat.search(lbl) for pat in shape_pats):
752+
continue
753+
approx_indices.append(i)
754+
if approx_indices:
755+
proto.approximate_meshes("convex_hull", shape_indices=approx_indices, keep_visual_shapes=True)
756+
else:
757+
proto.approximate_meshes("convex_hull", keep_visual_shapes=True)
758+
714759
# Add each env as a separate Newton world
715760
xform_cache = UsdGeom.XformCache()
716761
for _, env_path in env_paths:

source/isaaclab_newton/test/physics/test_sdf_config.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,8 @@ def test_builds_sdf_with_max_resolution(self):
4242

4343
mesh.build_sdf.assert_called_once_with(narrow_band_range=(-0.1, 0.1), max_resolution=128)
4444

45-
def test_clears_existing_sdf_before_rebuild(self):
46-
"""Existing SDF on mesh is cleared before building a new one."""
45+
def test_skips_rebuild_when_sdf_already_exists(self):
46+
"""Existing SDF on mesh is preserved (shared by reference from prototype)."""
4747
from isaaclab_newton.physics.newton_manager import NewtonManager
4848

4949
mesh = MagicMock()
@@ -52,8 +52,8 @@ def test_clears_existing_sdf_before_rebuild(self):
5252

5353
NewtonManager._build_sdf_on_mesh(mesh, sdf_cfg, None, "test_label")
5454

55-
mesh.clear_sdf.assert_called_once()
56-
mesh.build_sdf.assert_called_once()
55+
mesh.clear_sdf.assert_not_called()
56+
mesh.build_sdf.assert_not_called()
5757

5858
def test_target_voxel_size_takes_precedence(self):
5959
"""When target_voxel_size is set, it is passed alongside max_resolution."""

0 commit comments

Comments
 (0)