Skip to content

fix: implement Fabric-aware get/set_local_poses in FabricFrameView#5381

Open
pv-nvidia wants to merge 3 commits intoisaac-sim:developfrom
pv-nvidia:fix/fabric-local-matrix
Open

fix: implement Fabric-aware get/set_local_poses in FabricFrameView#5381
pv-nvidia wants to merge 3 commits intoisaac-sim:developfrom
pv-nvidia:fix/fabric-local-matrix

Conversation

@pv-nvidia
Copy link
Copy Markdown

Summary

Implement Fabric-aware get_local_poses() and set_local_poses() in FabricFrameView, computing local poses from Fabric world matrices instead of falling back to stale USD data.

Problem

After calling set_world_poses() in Fabric mode, get_local_poses() returned stale USD values because it delegated entirely to UsdFrameView. The Fabric worldMatrix was updated but the USD xformOps were not, so the local pose was inconsistent with the world pose.

This was Piotr's Issue #5 (localMatrix).

Solution

  • get_local_poses: Read child world pose from Fabric, parent world pose from USD (parents are not tracked in Fabric), compute local = inv(parent_world) * child_world
  • set_local_poses: Read parent world from USD, compute child_world = parent_world * local, write to Fabric via set_world_poses()

Added quaternion math helpers (_quat_mul, _quat_conjugate, _quat_rotate) for parent/child transform composition using (x, y, z, w) convention.

Test Results

# Fabric contract tests (test_set_world_updates_local now PASSES)
18 passed, 16 skipped (CPU)

# Camera tests
12 passed

# USD contract tests
45 passed

Dependencies

Depends on PR #5380 (fix/fabric-prepare-for-reuse).

@github-actions github-actions Bot added bug Something isn't working isaac-sim Related to Isaac Sim team isaac-lab Related to Isaac Lab team labels Apr 23, 2026
Copy link
Copy Markdown

@isaaclab-review-bot isaaclab-review-bot Bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🤖 Isaac Lab Review Bot

Summary

This PR fixes a correctness bug where get_local_poses() returned stale USD data after set_world_poses() was called in Fabric mode. The fix computes local poses from Fabric world matrices using proper parent-child transform math. It also removes the sync_usd_on_fabric_write workaround in favor of PrepareForReuse() for renderer notification.

Architecture Impact

Moderate cross-module impact. The FabricFrameView is used by Camera sensor (via FrameView factory). The removal of sync_usd_on_fabric_write=True from camera.py:409 means camera pose updates no longer write back to USD — this is intentional but changes observable behavior. Any downstream code that read camera poses from USD after Fabric writes would now see stale data. The _get_parent_world_poses method reads parent transforms from USD (since parents aren't tracked in Fabric), creating a hybrid USD/Fabric data flow that could have consistency issues if parent transforms are also modified via Fabric elsewhere.

Implementation Verdict

Minor fixes needed — The core math is correct but there are subtle issues with quaternion normalization, repeated torch imports, and a potential performance concern with the _prepare_for_reuse placement.

Test Coverage

Good coverage for the happy path. The PR adds:

  • test_fabric_set_world_does_not_write_back_to_usd — validates removal of sync behavior
  • test_prepare_for_reuse_detects_topology_change — validates PrepareForReuse API
  • test_camera_pose_update_reflected_in_render — validates end-to-end camera pose propagation

Missing: No test for set_local_poses in Fabric mode (the inverse of the fixed get_local_poses). The contract test test_set_world_updates_local only tests get, not set. No test for non-identity parent orientations which exercises the quaternion math more thoroughly.

CI Status

No CI checks available yet.

Findings

🟡 Warning: fabric_frame_view.py:253 — Missing quaternion normalization after multiplication
The quaternion multiply _quat_mul does not normalize the result. While mathematically the product of two unit quaternions is a unit quaternion, floating-point error accumulates. After _compose_parent_local and _invert_parent_compose, the output quaternions should be normalized to prevent drift, especially if these local poses are used iteratively:

# _compose_parent_local and _invert_parent_compose should normalize:
child_ori = FabricFrameView._quat_mul(parent_ori, local_ori)
child_ori = child_ori / child_ori.norm(dim=-1, keepdim=True)  # Add normalization

🟡 Warning: fabric_frame_view.py:144,187,294,333 — _prepare_for_reuse() called on every get/set operation
_prepare_for_reuse() is now called on every set_world_poses, get_world_poses, set_scales, and get_scales. This includes a potential _rebuild_fabric_arrays() call with kernel launches. For high-frequency pose queries (e.g., every simulation step), this adds overhead. The original code only called it on writes. Consider whether it's truly needed on reads, or if it should only be called before renders:

# In get_world_poses, line 187 — is this necessary?
self._prepare_for_reuse()  # Called every frame even if no writes happened

🔵 Improvement: fabric_frame_view.py:230,262,479,503 — Repeated import torch inside methods
The import torch statement appears inside set_local_poses (line 230), get_local_poses (line 262), _get_parent_world_poses (line 416), _quat_mul (line 479), and _quat_rotate (line 503). While Python caches module imports, this is unconventional. Move to top-level import since torch is already imported at module level (line 12).

🔵 Improvement: fabric_frame_view.py:248-251 — Identity quaternion allocation inefficient

local_ori = torch.tensor([[0.0, 0.0, 0.0, 1.0]] * count, ...)

This creates a Python list then converts to tensor. Use torch.zeros with index assignment or torch.tile:

local_ori = torch.zeros((count, 4), dtype=torch.float32, device=self._device)
local_ori[..., 3] = 1.0

🔵 Improvement: fabric_frame_view.py:237 — indices_list = wp.to_torch(indices_wp).long().tolist()
Converting GPU tensor to Python list forces a GPU→CPU sync and creates Python objects. This happens in both set_local_poses and get_local_poses. For large batch sizes, this is inefficient. Consider keeping indices on GPU if possible, or at minimum document this as a known limitation.

🟡 Warning: test_tiled_camera.py:214-268 — Test uses fixture's setup_camera but creates its own SimulationContext
The test_camera_pose_update_reflected_in_render test takes setup_camera fixture but ignores its sim and camera_cfg, creating a new CameraCfg. This works but the fixture's scene (_populate_scene) is used while the fixture's camera config is discarded. The interaction is confusing — the test relies on setup_camera for scene setup and teardown but not for camera config. Consider either using the fixture's config or creating a separate fixture.

🔵 Improvement: fabric_frame_view.py:420-440 — Parent path extraction via string manipulation

parent_path = child_path.rsplit("/", 1)[0]
parent_prim = stage.GetPrimAtPath(parent_path)

USD has a proper API for this: prim.GetParent(). Using string manipulation could fail for edge cases (e.g., root prims). The code does handle the "no parent" case, but using the USD API is more robust:

child_prim = stage.GetPrimAtPath(child_path)
parent_prim = child_prim.GetParent()

@greptile-apps
Copy link
Copy Markdown
Contributor

greptile-apps Bot commented Apr 23, 2026

Greptile Summary

This PR implements Fabric-aware get_local_poses() and set_local_poses() in FabricFrameView, replacing the stale-USD-data fallback by computing local poses from Fabric world matrices via quaternion composition helpers. It also removes the sync_usd_on_fabric_write workaround in favour of calling PrepareForReuse() on every Fabric get/set to notify the renderer and detect topology changes.

  • _rebuild_fabric_arrays (called on topology change) rebuilds the view↔fabric index mappings and world-matrix fabricarray but does not rebuild _fabric_positions_buf, _fabric_orientations_buf, or _fabric_scales_buf. These cached output buffers are used by the use_cached paths in get_world_poses/get_scales; if a topology event shifts the effective fabricarray shape they will be the wrong size for subsequent kernel launches.
  • In the set_local_poses fallback path (Fabric initialised but not yet synced), _fabric_hierarchy.update_world_xforms() is called and Fabric is correctly updated, but _fabric_usd_sync_done is never flipped to True, causing a redundant full USD→Fabric re-sync on the next read.

Confidence Score: 4/5

Safe to merge after addressing the _rebuild_fabric_arrays output-buffer gap; all other findings are style/efficiency improvements.

One P1 finding: _rebuild_fabric_arrays omits rebuilding the cached output buffers (_fabric_positions_buf, etc.), which are used in the hot get_world_poses/get_scales paths and could become the wrong size after a topology event. The rest of the findings are P2 (dead code, redundant imports, missed sync flag). The core quaternion math is verified correct and the PrepareForReuse design is sound.

source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py — specifically _rebuild_fabric_arrays and the set_local_poses fallback path.

Important Files Changed

Filename Overview
source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py Core change: Fabric-aware get/set_local_poses implemented; _prepare_for_reuse added on all Fabric get/set operations; sync_usd_on_fabric_write removed. Issues: _rebuild_fabric_arrays omits output buffer rebuilds (P1), _fabric_usd_sync_done not set in fallback set_local_poses path (P2), unused count variable and redundant imports (P2).
source/isaaclab/isaaclab/sensors/camera/camera.py Removes sync_usd_on_fabric_write=True from FrameView construction; updates comment to reflect PrepareForReuse approach. Clean change.
source/isaaclab/isaaclab/sim/views/usd_frame_view.py Minor docstring update removing the sync_usd_on_fabric_write mention from kwargs description. No logic changes.
source/isaaclab/test/sensors/test_tiled_camera.py Adds parametrized test validating camera pose changes are reflected in rendered depth (close vs. far position). Relies on existing setup_camera fixture; logic is sound.
source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py Removes sync_usd_on_fabric_write from view construction; adds tests verifying no USD writeback and PrepareForReuse bool return. Tests are well-structured and cover the key behavioral change.
apps/isaaclab.python.headless.rendering.kit Adds omni.kit.viewport.window and omni.kit.hydra_texture extensions for headless render-product/annotator support. No code issues.

Flowchart

%%{init: {'theme': 'neutral'}}%%
flowchart TD
    A[set_local_poses called] --> B{use_fabric AND\nfabric_initialized AND\nfabric_usd_sync_done?}
    B -- No --> C[usd_view.set_local_poses]
    C --> D{use_fabric AND\nfabric_initialized?}
    D -- Yes --> E[update_world_xforms\n+ _prepare_for_reuse]
    D -- No --> F[return]
    E --> F
    B -- Yes --> G[_get_parent_world_poses\nfrom USD XformCache]
    G --> H[compose child_world =\nparent_world x local]
    H --> I[set_world_poses to Fabric]

    J[get_local_poses called] --> K{use_fabric AND\nfabric_initialized AND\nfabric_usd_sync_done?}
    K -- No --> L[usd_view.get_local_poses]
    K -- Yes --> M[get_world_poses from Fabric]
    M --> N[_get_parent_world_poses\nfrom USD XformCache]
    N --> O[local = inv_parent x child_world]
    O --> P[return wp.array local poses]

    Q[_prepare_for_reuse] --> R{fabric_selection\ninitialized?}
    R -- No --> S[return]
    R -- Yes --> T[PrepareForReuse]
    T --> U{topology\nchanged?}
    U -- Yes --> V[_rebuild_fabric_arrays\nmappings + world matrices\n NOT output buffers]
    U -- No --> W[continue]
Loading

Reviews (1): Last reviewed commit: "fix: implement Fabric-aware get/set_loca..." | Re-trigger Greptile

Comment on lines +390 to +403
def _rebuild_fabric_arrays(self) -> None:
"""Rebuild fabricarray and view↔fabric mappings after a topology change."""
self._view_to_fabric = wp.zeros((self.count,), dtype=wp.uint32, device=self._fabric_device)
self._fabric_to_view = wp.fabricarray(self._fabric_selection, self._view_index_attr)

wp.launch(
kernel=fabric_utils.set_view_to_fabric_array,
dim=self._fabric_to_view.shape[0],
inputs=[self._fabric_to_view, self._view_to_fabric],
device=self._fabric_device,
)
wp.synchronize()

self._fabric_world_matrices = wp.fabricarray(self._fabric_selection, "omni:fabric:worldMatrix")
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P1 _rebuild_fabric_arrays leaves output buffers stale after topology change

After a topology change _rebuild_fabric_arrays correctly re-creates _view_to_fabric, _fabric_to_view, and _fabric_world_matrices, but it leaves _fabric_positions_buf, _fabric_orientations_buf, and _fabric_scales_buf pointing at the old allocations. These buffers are sized to (self.count, N) and are used as output arrays in the get_world_poses / get_scales kernel launches. If a topology event changes the effective count of prims held by _fabric_selection (even within the same selection, through compaction that alters the fabricarray shape), the kernel launch will size-mismatch against the stale use_cached path buffers.

Add buffer rebuilds alongside the existing array rebuilds:

self._fabric_positions_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._fabric_device)
self._fabric_orientations_buf = wp.zeros((self.count, 4), dtype=wp.float32, device=self._fabric_device)
self._fabric_scales_buf = wp.zeros((self.count, 3), dtype=wp.float32, device=self._fabric_device)

Comment on lines 225 to +232
def set_local_poses(self, translations=None, orientations=None, indices=None):
self._usd_view.set_local_poses(translations, orientations, indices)
if not self._use_fabric or not self._fabric_initialized or not self._fabric_usd_sync_done:
self._usd_view.set_local_poses(translations, orientations, indices)
if self._use_fabric and self._fabric_initialized:
# After writing local to USD, recompute Fabric world matrices
self._fabric_hierarchy.update_world_xforms()
self._prepare_for_reuse()
return
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P2 _fabric_usd_sync_done not updated after fallback set_local_poses

When the fallback branch runs (_fabric_usd_sync_done is False but Fabric is initialized), the code writes local poses to USD and then calls _fabric_hierarchy.update_world_xforms(), which propagates those new local transforms into Fabric world matrices. At that point Fabric IS in sync with USD, yet _fabric_usd_sync_done is never set to True. The next call to get_world_poses therefore calls _sync_fabric_from_usd_once(), which repeats the set_world_poses / set_scales kernel launches unnecessarily.

            self._fabric_hierarchy.update_world_xforms()
            self._prepare_for_reuse()
            self._fabric_usd_sync_done = True   # ← add this
        return

Comment on lines +268 to +270
indices_wp = self._resolve_indices_wp(indices)
count = indices_wp.shape[0]
indices_list = wp.to_torch(indices_wp).long().tolist()
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P2 count variable computed but never used in get_local_poses

count is assigned from indices_wp.shape[0] but is not referenced anywhere else in the method. Remove the dead assignment to keep the code clean.

Suggested change
indices_wp = self._resolve_indices_wp(indices)
count = indices_wp.shape[0]
indices_list = wp.to_torch(indices_wp).long().tolist()
indices_wp = self._resolve_indices_wp(indices)
indices_list = wp.to_torch(indices_wp).long().tolist()

Comment on lines +481 to +495
def _quat_mul(q1: "torch.Tensor", q2: "torch.Tensor") -> "torch.Tensor":
"""Quaternion multiply (x,y,z,w) convention."""
x1, y1, z1, w1 = q1[..., 0:1], q1[..., 1:2], q1[..., 2:3], q1[..., 3:4]
x2, y2, z2, w2 = q2[..., 0:1], q2[..., 1:2], q2[..., 2:3], q2[..., 3:4]
import torch

return torch.cat(
[
w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2,
w1 * y2 - x1 * z2 + y1 * w2 + z1 * x2,
w1 * z2 + x1 * y2 - y1 * x2 + z1 * w2,
w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2,
],
dim=-1,
)
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

P2 Redundant import torch inside @staticmethod methods

torch is already imported at module level (line 13). The inline import torch statements inside _quat_mul and _quat_rotate are redundant; Python's module cache makes them harmless but they add noise. The same pattern appears in get_local_poses and set_local_poses — the module-level import covers all of them.

@pv-nvidia
Copy link
Copy Markdown
Author

Code Coverage — fabric_frame_view.py

Name                   Stmts   Miss  Cover   Missing
------------------------------------------------------
fabric_frame_view.py     279     41    85%   ...

Coverage breakdown (this PR adds local pose support):

  • get_local_poses Fabric path: covered by test_set_world_updates_local
  • set_local_poses Fabric path: covered by test_set_local_via_fabric_path (new)
  • get_scales Fabric path: covered by test_get_scales_fabric_path (new)
  • _get_parent_world_poses: covered
  • _compose_parent_local / _invert_parent_compose: covered
  • _quat_mul / _quat_conjugate / _quat_rotate: covered
  • ⬜ CPU fallback paths: not tested (CPU skips — Warp fabricarray limitation)
  • set_scales: not tested (no set_scales in contract suite)
  • ⬜ Topology rebuild branch: not triggered during tests

Test results (20 passed, 16 CPU-skipped):

  • All 18 contract tests pass on cuda:0 (no xfails — test_set_world_updates_local now passes!)
  • test_set_local_via_fabric_path ✅ (new — exercises Fabric-native local→world)
  • test_get_scales_fabric_path ✅ (new — exercises Fabric-native scale read)

@pv-nvidia pv-nvidia force-pushed the fix/fabric-local-matrix branch 4 times, most recently from 58ce0b6 to 5b1b255 Compare April 24, 2026 13:34
…c_write

Replace the sync_usd_on_fabric_write workaround with proper
PrepareForReuse() calls on the Fabric PrimSelection.  This tells
the renderer (FSD/Storm) that Fabric data is about to be
modified, so the next rendered frame reflects updated transforms.

Key changes:
- FabricFrameView: call _prepare_for_reuse() before every Fabric
  read/write to notify the renderer and detect topology changes
- FabricFrameView: remove sync_usd_on_fabric_write parameter
  (deprecated with warning via **kwargs for backward compat)
- FabricFrameView: add _rebuild_fabric_arrays() for topology change
  recovery when PrepareForReuse() returns True
- camera.py: remove sync_usd_on_fabric_write=True from FrameView
  construction (PrepareForReuse makes it unnecessary)
- usd_frame_view.py: clean stale docstring reference

Tests added:
- test_camera_pose_update_reflected_in_render: validates camera pose
  changes propagate to rendered depth (close vs far position) for
  both CPU and GPU paths, tiled and non-tiled cameras
- test_fabric_set_world_does_not_write_back_to_usd: confirms Fabric
  writes stay in Fabric without USD writeback
- test_prepare_for_reuse_detects_topology_change: validates the
  PrepareForReuse API returns correct topology status
- xfail for test_set_world_updates_local (Issue isaac-sim#5: localMatrix
  not updated from Fabric world pose — tracked separately)

Also includes headless rendering kit deps (viewport.window +
hydra_texture) needed for camera render tests.

Addresses Piotr's Issue isaac-sim#1 (USD write-back) and Issue isaac-sim#4
(PrepareForReuse / renderer notification).
Compute local poses from Fabric world matrices instead of falling
back to stale USD data.  This fixes the inconsistency where
set_world_poses() modified Fabric worldMatrix but get_local_poses()
still read from USD, returning stale values (Issue isaac-sim#5).

How it works:
- get_local_poses: reads child world pose from Fabric, parent world
  pose from USD, computes local = inv(parent) * child
- set_local_poses: reads parent world from USD, computes child world
  = parent * local, writes to Fabric via set_world_poses

Added quaternion math helpers (_quat_mul, _quat_conjugate,
_quat_rotate) for the parent/child transform composition.

Test changes:
- Remove xfail from test_set_world_updates_local (now passes)

Addresses Piotr's Issue isaac-sim#5 (localMatrix).

Depends on: fix/fabric-prepare-for-reuse (PR isaac-sim#5380)
Adds two new tests to improve code coverage of FabricFrameView:

- test_set_local_via_fabric_path: Exercises the Fabric-native
  set_local_poses code path (parent_world * local → child_world)
  by first triggering Fabric init via get_world_poses, then
  setting local poses and verifying world = parent + local.

- test_get_scales_fabric_path: Exercises the Fabric-native
  get_scales path, verifying default scale (1,1,1) is returned.

Coverage of fabric_frame_view.py: 76% → 85%.
@pv-nvidia pv-nvidia force-pushed the fix/fabric-local-matrix branch from 5b1b255 to c32cce4 Compare April 24, 2026 21:12
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

bug Something isn't working isaac-lab Related to Isaac Lab team isaac-sim Related to Isaac Sim team

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant