Skip to content

Commit bab8ca0

Browse files
committed
Tighten FabricFrameView lifecycle and verify transpose math
Three review fixes plus the missing coverage for the transpose storage convention. * Hierarchy cache eviction: cache key is now (stage_id, fabric_id) so a recycled stage_id paired with a new Fabric attachment never returns a stale handle. Added FabricFrameView.clear_static_caches() classmethod for explicit teardown and wired it into the test fixture so cached handles do not accumulate across the suite. * PrepareForReuse no longer fires twice per sync. Both _sync_local_from_world and _sync_world_from_local_if_dirty refresh trans_sel_ro exactly once, then read _world_ifa_ro / _local_ifa_ro / _parent_world_ifa_ro directly from the fields instead of going through the accessors. * Class docstring rewritten to describe the actual PrepareForReuse policy (every accessor calls it; idempotent and cheap in the steady state). The prior wording claimed reads avoided PrepareForReuse, which has not been true since the indexedfabricarray rewrite. * New regression tests for the transpose storage convention. The standard fixture parents are translation-only, so the rotation block is identity and equal to its transpose - which means a wrong transpose convention would still pass every existing test. Two new tests place a parent rotated 90 degrees around Z and verify the world<->local round-trip: - test_set_local_then_get_world_with_rotated_parent exercises update_indexed_world_matrix_from_local - test_set_world_then_get_local_with_rotated_parent exercises update_indexed_local_matrix_from_world Confirmed locally that flipping the multiply order in either kernel makes the matching test fail. 45 tests pass on cpu and cuda:0.
1 parent 82ed7ea commit bab8ca0

2 files changed

Lines changed: 137 additions & 25 deletions

File tree

source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py

Lines changed: 56 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -80,12 +80,18 @@ class FabricFrameView(BaseFrameView):
8080
``omni:fabric:localMatrix``. All other operations delegate to the
8181
internal USD view.
8282
83-
After every Fabric write (``set_world_poses``, ``set_local_poses``,
84-
``set_scales``), :meth:`PrepareForReuse` is called on the
85-
``PrimSelection`` to notify the FSD renderer that Fabric data has
86-
changed and to detect topology changes that require rebuilding
87-
internal mappings. Read operations do not call PrepareForReuse to
88-
avoid unnecessary renderer invalidation.
83+
Every accessor for a selection's indexed fabric array
84+
(:meth:`_get_world_ro_array`, :meth:`_get_local_ro_array`,
85+
:meth:`_get_world_rw_array`, :meth:`_get_local_rw_array`,
86+
:meth:`_get_parent_world_ro_array`) calls :meth:`PrepareForReuse` on its
87+
backing ``PrimSelection`` to detect Fabric topology changes that would
88+
require rebuilding the view→fabric index mapping. ``PrepareForReuse``
89+
is idempotent and cheap in the steady state (returns ``False`` with no
90+
rebuild), so the per-access cost is negligible. The two sync helpers
91+
(:meth:`_sync_local_from_world`, :meth:`_sync_world_from_local_if_dirty`)
92+
refresh ``trans_sel_ro`` at most once per call to avoid the redundant
93+
USDRT round-trip that would otherwise occur when ``_world_ifa_ro``,
94+
``_local_ifa_ro`` and ``_parent_world_ifa_ro`` are read consecutively.
8995
9096
Pose getters return :class:`~isaaclab.utils.warp.ProxyArray`. Setters accept ``wp.array``.
9197
"""
@@ -94,12 +100,29 @@ class FabricFrameView(BaseFrameView):
94100
_LOCAL_MATRIX_NAME = "omni:fabric:localMatrix"
95101

96102
# Stage-level shared state. Multiple FabricFrameView instances on the same stage
97-
# share one IFabricHierarchy handle. ``ClassVar`` plus the ``_static_`` prefix
98-
# make it explicit (and enforceable by type checkers) that this is class-level —
99-
# never shadow it with ``self.<name> = ...``. The cache is not protected by a
100-
# lock; Isaac Lab's simulation loop is single-threaded, and adding locking would
101-
# negate the per-stage hit-cache cost it exists to avoid.
102-
_static_hierarchy_cache: ClassVar[dict[int, object]] = {}
103+
# share one ``IFabricHierarchy`` handle, keyed by ``(stage_id, fabric_id)`` so
104+
# that a recycled ``stage_id`` paired with a fresh ``fabric_id`` never reuses a
105+
# stale handle. ``ClassVar`` plus the ``_static_`` prefix make it explicit (and
106+
# enforceable by type checkers) that this is class-level — never shadow it with
107+
# ``self.<name> = ...``. The cache is not protected by a lock; Isaac Lab's
108+
# simulation loop is single-threaded, and adding locking would negate the
109+
# per-stage hit-cache cost it exists to avoid. Call
110+
# :meth:`clear_static_caches` on stage teardown if you tear down many stages
111+
# in one process.
112+
_static_hierarchy_cache: ClassVar[dict[tuple[int, int], object]] = {}
113+
114+
@classmethod
115+
def clear_static_caches(cls) -> None:
116+
"""Drop all cached ``IFabricHierarchy`` handles.
117+
118+
Call this after tearing down a USD stage if the process will continue
119+
opening new stages. Cached handles are otherwise retained for the
120+
lifetime of the process, which can leak memory in long test suites and,
121+
in theory, allow a recycled ``stage_id`` paired with a new Fabric
122+
attachment to read a stale handle (though the ``(stage_id, fabric_id)``
123+
cache key already guards against the latter).
124+
"""
125+
cls._static_hierarchy_cache.clear()
103126

104127
def __init__(
105128
self,
@@ -451,14 +474,15 @@ def _sync_world_from_local_if_dirty(self) -> None:
451474
"""
452475
if not self._world_dirty:
453476
return
454-
# Make sure the parent indexed array is up-to-date with the current trans selection.
455-
if self._parent_world_ifa_ro is None:
456-
self._parent_world_ifa_ro = self._build_parent_indexed_array(self._trans_sel_ro)
477+
# Refresh trans_sel_ro once, then read _local_ifa_ro and _parent_world_ifa_ro
478+
# directly to avoid calling PrepareForReuse twice on the same selection.
479+
if self._trans_sel_ro.PrepareForReuse() or self._parent_world_ifa_ro is None:
480+
self._rebuild_trans_ro_arrays()
457481
wp.launch(
458482
kernel=fabric_utils.update_indexed_world_matrix_from_local,
459483
dim=self.count,
460484
inputs=[
461-
self._get_local_ro_array(),
485+
self._local_ifa_ro,
462486
self._parent_world_ifa_ro,
463487
self._get_world_rw_array(),
464488
self._view_indices,
@@ -476,12 +500,15 @@ def _sync_local_from_world(self, indices_wp: wp.array) -> None:
476500
not provide a built-in world → local sync, so we do it via a Warp kernel
477501
using the parent indexed fabric array.
478502
"""
503+
# Refresh trans_sel_ro once; _world_ifa_ro and _parent_world_ifa_ro share it.
504+
if self._trans_sel_ro.PrepareForReuse() or self._parent_world_ifa_ro is None:
505+
self._rebuild_trans_ro_arrays()
479506
wp.launch(
480507
kernel=fabric_utils.update_indexed_local_matrix_from_world,
481508
dim=indices_wp.shape[0],
482509
inputs=[
483-
self._get_world_ro_array(),
484-
self._get_parent_world_ro_array(),
510+
self._world_ifa_ro,
511+
self._parent_world_ifa_ro,
485512
self._get_local_rw_array(),
486513
indices_wp,
487514
],
@@ -611,18 +638,22 @@ def _initialize_fabric(self) -> None:
611638
self._stage = usdrt.Usd.Stage.Attach(self._stage_id)
612639
self._stage.SynchronizeToFabric()
613640

614-
# Reuse (or create) a hierarchy handle for this stage. Enable change-tracking
641+
# Reuse (or create) a hierarchy handle for this stage. The cache key is
642+
# ``(stage_id, fabric_id)`` so a recycled ``stage_id`` paired with a fresh
643+
# Fabric attachment never returns a stale handle. Enable change-tracking
615644
# BEFORE we author any local matrices, so the per-prim
616-
# ``SetLocalXformFromUsd`` calls below mark themselves dirty and the next
617-
# ``update_world_xforms()`` walks the parent chain to populate worldMatrix.
618-
if self._stage_id not in FabricFrameView._static_hierarchy_cache:
645+
# ``SetLocalXformFromUsd`` calls below mark themselves dirty.
646+
fabric_id = self._stage.GetFabricId()
647+
self._fabric_id = fabric_id
648+
cache_key = (self._stage_id, fabric_id)
649+
if cache_key not in FabricFrameView._static_hierarchy_cache:
619650
hierarchy = usdrt.hierarchy.IFabricHierarchy().get_fabric_hierarchy(
620-
self._stage.GetFabricId(), self._stage.GetStageIdAsStageId()
651+
fabric_id, self._stage.GetStageIdAsStageId()
621652
)
622653
hierarchy.track_local_xform_changes(True)
623654
hierarchy.track_world_xform_changes(True)
624-
FabricFrameView._static_hierarchy_cache[self._stage_id] = hierarchy
625-
self._fabric_hierarchy = FabricFrameView._static_hierarchy_cache[self._stage_id]
655+
FabricFrameView._static_hierarchy_cache[cache_key] = hierarchy
656+
self._fabric_hierarchy = FabricFrameView._static_hierarchy_cache[cache_key]
626657

627658
# Ensure each child prim AND its parent have BOTH Fabric world and local matrix
628659
# attributes. Our ``trans_ro`` selection requires both, so prims missing either

source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py

Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,9 @@ def test_setup_teardown():
4141
yield
4242
sim_utils.clear_stage()
4343
sim_utils.SimulationContext.clear_instance()
44+
# Each test creates a fresh stage; drop cached IFabricHierarchy handles so
45+
# the next test does not reuse a handle attached to the disposed stage.
46+
FrameView.clear_static_caches()
4447

4548

4649
def _skip_if_unavailable(device: str):
@@ -276,3 +279,81 @@ def test_get_scales_fabric_path(device, view_factory):
276279
# Default scale should be (1, 1, 1)
277280
expected = torch.tensor([[1.0, 1.0, 1.0]], dtype=torch.float32, device=device)
278281
torch.testing.assert_close(scales_t, expected, atol=1e-4, rtol=0)
282+
283+
284+
# ------------------------------------------------------------------
285+
# Transpose-convention verification: world ↔ local kernels rely on the
286+
# identity ``(A·B)ᵀ = Bᵀ·Aᵀ`` to drop explicit transposes when operating
287+
# on Fabric's column-transposed matrix storage. The translation-only
288+
# parents used by the standard fixture cannot distinguish the right
289+
# convention from the wrong one — the rotation block is identity and
290+
# equals its own transpose. These tests use a parent rotated 90° around
291+
# Z so that an incorrect storage convention would produce a clearly
292+
# wrong child pose.
293+
# ------------------------------------------------------------------
294+
295+
296+
# Parent at (0, 0, 1) rotated +90° around Z (so the parent X axis points
297+
# along world +Y). Quaternion components in (x, y, z, w) order.
298+
_ROTATED_PARENT_POS = (0.0, 0.0, 1.0)
299+
_ROTATED_PARENT_QUAT_XYZW = (0.0, 0.0, 0.70710678, 0.70710678)
300+
301+
302+
def _build_rotated_parent_view(device: str) -> "FrameView":
303+
"""Build a 1-env FabricFrameView whose parent is rotated 90° around Z."""
304+
stage = sim_utils.get_current_stage()
305+
sim_utils.create_prim(
306+
"/World/Parent_0",
307+
"Xform",
308+
translation=_ROTATED_PARENT_POS,
309+
orientation=_ROTATED_PARENT_QUAT_XYZW,
310+
stage=stage,
311+
)
312+
sim_utils.create_prim("/World/Parent_0/Child", "Camera", translation=(0.0, 0.0, 0.0), stage=stage)
313+
sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, device=device, use_fabric=True))
314+
view = FrameView("/World/Parent_.*/Child", device=device)
315+
view.get_world_poses() # force Fabric init and USD→Fabric seed
316+
return view
317+
318+
319+
@pytest.mark.parametrize("device", ["cpu", "cuda:0"])
320+
def test_set_local_then_get_world_with_rotated_parent(device):
321+
"""Verify ``update_indexed_world_matrix_from_local`` under non-identity parent rotation.
322+
323+
With parent rotated +90° around Z, a child local translation of (1, 0, 0)
324+
must produce world translation (0, 1, 1) — parent_pos + R · local. If the
325+
transpose convention in the kernel were wrong, the rotation would flip
326+
direction and the world position would land at (0, -1, 1) instead.
327+
"""
328+
_skip_if_unavailable(device)
329+
view = _build_rotated_parent_view(device)
330+
331+
new_local = wp.zeros((1, 3), dtype=wp.float32, device=device)
332+
wp.launch(kernel=_fill_position, dim=1, inputs=[new_local, 1.0, 0.0, 0.0], device=device)
333+
identity_quat = wp.from_torch(torch.tensor([[0.0, 0.0, 0.0, 1.0]], dtype=torch.float32, device=device))
334+
view.set_local_poses(translations=new_local, orientations=identity_quat)
335+
336+
world_pos, _ = view.get_world_poses()
337+
expected = torch.tensor([[0.0, 1.0, 1.0]], dtype=torch.float32, device=device)
338+
torch.testing.assert_close(world_pos.torch, expected, atol=1e-5, rtol=0)
339+
340+
341+
@pytest.mark.parametrize("device", ["cpu", "cuda:0"])
342+
def test_set_world_then_get_local_with_rotated_parent(device):
343+
"""Verify ``update_indexed_local_matrix_from_world`` under non-identity parent rotation.
344+
345+
With parent rotated +90° around Z and at (0, 0, 1), writing child world
346+
translation (5, 0, 2) must yield child local translation Rᵀ · (5, 0, 1) =
347+
(0, -5, 1). A wrong transpose convention would invert the rotation in the
348+
wrong direction and produce (0, 5, 1) instead.
349+
"""
350+
_skip_if_unavailable(device)
351+
view = _build_rotated_parent_view(device)
352+
353+
new_world = wp.zeros((1, 3), dtype=wp.float32, device=device)
354+
wp.launch(kernel=_fill_position, dim=1, inputs=[new_world, 5.0, 0.0, 2.0], device=device)
355+
view.set_world_poses(positions=new_world)
356+
357+
local_pos, _ = view.get_local_poses()
358+
expected = torch.tensor([[0.0, -5.0, 1.0]], dtype=torch.float32, device=device)
359+
torch.testing.assert_close(local_pos.torch, expected, atol=1e-5, rtol=0)

0 commit comments

Comments
 (0)