Skip to content

feat: Fabric-accelerated get/set_local_poses via indexedfabricarray#5677

Open
pv-nvidia wants to merge 39 commits into
isaac-sim:developfrom
pv-nvidia:pv/fabric-local-poses
Open

feat: Fabric-accelerated get/set_local_poses via indexedfabricarray#5677
pv-nvidia wants to merge 39 commits into
isaac-sim:developfrom
pv-nvidia:pv/fabric-local-poses

Conversation

@pv-nvidia

@pv-nvidia pv-nvidia commented May 18, 2026

Copy link
Copy Markdown
Contributor

feat: Fabric-accelerated get/set_local_poses via indexedfabricarray

Adds GPU-accelerated get_local_poses / set_local_poses (and the explicit
get/set_local_scales, get/set_world_scales) to FabricFrameView, using
wp.indexedfabricarray over Fabric's omni:fabric:worldMatrix and
omni:fabric:localMatrix. Both directions stay in sync via lazy Warp-kernel
recomputes (no round-trip through USD).

Builds on Piotr's prototype at
bareya/pbarejko/camera-update.

Benchmark (1024 prims, 50 iterations, A6000)

Operation USD (ms) Fabric (ms) Speedup
Get World Poses 13.56 0.067 201×
Set World Poses 29.97 0.123 244×
Interleaved Set→Get 43.78 0.159 276×
Get Local Poses 6.15 0.064 96×
Set Local Poses 8.61 0.053 163×

Why two layers of indirection: wp.indexedfabricarray

Naive wp.fabricarray(selection, attr) already wraps a Fabric attribute as a
Warp array, but it indexes by selection order, which is opaque to user
code and unstable across Fabric reallocation. wp.indexedfabricarray(fa, indices) overlays a view-side index array on top, so kernels can write
fabric_matrices[view_index] and have it land at the right Fabric slot
regardless of internal layout. Topology changes are detected per-selection
via PrepareForReuse(); the indices and indexed arrays are rebuilt lazily
on the next access.

Why RO/RW PrimSelections are required

The separate RO/RW PrimSelections are not an implementation detail; they are the synchronization contract with Fabric's hierarchy updater. Fabric/Kit runs IFabricHierarchy.update_world_xforms() on the render path, after Isaac Lab has written matrices but before Hydra/RTX consumes omni:fabric:worldMatrix. That updater decides which direction is authoritative from the access flags on the most recent selection:

  • worldMatrix=RW, localMatrix=RO means the user authored world transforms; Fabric must not rebuild world from stale local data.
  • worldMatrix=RO, localMatrix=RW means the user authored local transforms; Fabric may rebuild world from the new local data.
  • worldMatrix=RW, localMatrix=RW is ambiguous and unsafe for this API: Fabric can treat local as canonical and overwrite a just-authored world matrix before the renderer reads it.

This is why the branch uses three persistent selections instead of one combined read/write selection. Dirty tracking keeps Isaac Lab's local/world getters consistent on demand; the asymmetric RO/RW selections keep the renderer-facing Fabric world matrices correct across the render tick.

The design that matters most: three selections with asymmetric RO/RW access

This is the load-bearing correctness choice and the reason the
implementation kept iterating. Three persistent PrimSelection handles
cover the same prims with different per-attribute access flags:

_trans_sel_ro  :  worldMatrix=RO, localMatrix=RO   reads + sync helpers
_world_sel_rw  :  worldMatrix=RW, localMatrix=RO   set_world_poses / _scales
_local_sel_rw  :  worldMatrix=RO, localMatrix=RW   set_local_poses / _scales

Kit runs IFabricHierarchy.update_world_xforms() as part of every render
tick, and that update respects the access flags: if localMatrix is
marked RO on the most recent write, Fabric leaves the user's worldMatrix
write alone; if localMatrix is marked RW, Fabric treats it as the
canonical source and recomputes world from local.

A single combined worldMatrix=RW, localMatrix=RW selection (one earlier
revision of this branch) removes that protection. Fabric sees both
attributes as user-authored, falls back to the hierarchy's canonical
direction (local → world), and recomputes worldMatrix from the still-stale
localMatrix. The user's worldMatrix write is silently overwritten before
the renderer reads it. That was the failure mode behind the
test_output_equal_to_usdcamera regression and any other Camera + RTX path
that drives world poses through Fabric (the RTX delegate consumes
omni:fabric:worldMatrix directly via Hydra's fabric transform reader).

The asymmetric RO/RW layout is the right primitive for that protection,
and it works with the lazy consistency model below rather than fighting it.

Lazy world ↔ local consistency

Setters mark the opposite direction stale on a small enum
(_DirtyFlag.{NONE,WORLD,LOCAL}); the recompute happens only when the
opposite getter is called. No eager Warp kernels run on the hot setter
path. Concretely:

  • set_world_poses / set_world_scales write worldMatrix and set
    _dirty = LOCAL. The next get_local_* recomputes localMatrix = inv(parent_world) * world via a Warp kernel.
  • set_local_poses / set_local_scales write localMatrix and set
    _dirty = WORLD. The next get_world_* recomputes `world = parent_world
    • local`.

If the user interleaves the two setters on the same view in a single
frame, the second one flushes the stale direction before writing (correct
but pays an extra kernel launch). A one-time warning per view instance
flags this so users notice the perf hazard. Sticking to one setter
exclusively keeps the path O(1) kernel launches.

Renderer correctness across the lazy gap is provided by the RO/RW
protection above, not by Isaac Lab doing extra work: between the user's
write and the renderer's read, the only thing that runs is Kit's
update_world_xforms tick, and that tick is well-behaved because the
access flags tell it what to leave alone.

Getter note: indexed Fabric getters intentionally return freshly allocated
ProxyArray buffers without an unconditional wp.synchronize(). Consumers
that need immediate host-visible data should synchronize or copy explicitly;
GPU consumers keep normal Warp stream ordering.

Earlier iterations on this PR (resolved)

For reviewers who saw the older shape of this branch:

  • An interim revision collapsed the three selections into one combined
    ReadWrite(world+local) selection. That broke the renderer-clobber
    protection described above; the latest commit restores the three-selection
    shape.
  • The same interim revision added an eager _flush_deferred_local_writes()
    to set_local_poses and a symmetric eager _sync_local_from_world_if_dirty()
    to set_world_poses as workarounds for the lost protection. These are
    removed in the latest commit -- they're unnecessary once the RO/RW layout
    is back, and they made every setter pay an extra kernel.
  • A change_block / changeBlock context manager was added on
    BaseFrameView and FabricFrameView to batch the now-removed eager
    flushes. With nothing to defer, the API has been removed too.

Net change vs. the previous push on this branch: -198 lines. Net change
vs. develop is dominated by the new set/get_local_* API and the new
indexed Warp kernels in isaaclab.utils.warp.fabric.

Tests

New / kept:

  • test_set_local_poses_roundtrip, test_set_local_then_get_world_with_rotated_parent,
    test_set_world_then_get_local_with_rotated_parent — local⇄world
    correctness, including a 90° Z-rotated parent that catches matrix-storage
    convention bugs.
  • test_initial_seed_with_scaled_parent — the initial USD-seed path
    composes scales correctly across non-unit-scale parents.
  • test_multi_view_per_view_dirty_isolation — two views on the same stage
    don't clear each other's dirty flag (regression for an earlier
    class-level-flag bug).
  • test_prepare_for_reuse_detects_topology_change — polls all three
    selections.
  • test_fabric_rebuild_after_topology_change — rebuilds each selection's
    indexed array after a simulated topology change.
  • test_interleaved_set_emits_warning — the one-time interleave warning.

Removed in the latest commit (obsolete contracts):

  • test_set_local_*_updates_renderer_facing_fabric_world_matrix — asserted
    the eager-update contract that the lazy design deliberately does not
    hold; renderer correctness is now provided by the RO/RW protection.
  • The four test_change_block_* tests — the API is gone.

Verified:

  • pytest test_ray_caster_camera.py::test_output_equal_to_usdcamera — passes
    (was the original failure that motivated the redesign).
  • pytest test_ray_caster_camera.py::test_output_equal_to_usd_camera_when_intrinsics_set
    4/4 pass.
  • pytest test_views_xform_prim_fabric.py — 71 passed, 3 skipped (cuda:1).
  • ./isaaclab.sh -f — clean.

Files changed

  • source/isaaclab/isaaclab/sim/views/base_frame_view.py
  • source/isaaclab/isaaclab/utils/warp/fabric.py (new indexed kernels)
  • source/isaaclab_physx/isaaclab_physx/sim/views/fabric_frame_view.py
  • source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py
  • source/isaaclab/test/sim/frame_view_contract_utils.py (extended contracts)
  • source/isaaclab/changelog.d/fabric-local-poses.rst
  • source/isaaclab_physx/changelog.d/fabric-local-poses.rst

@github-actions github-actions Bot added documentation Improvements or additions to documentation isaac-lab Related to Isaac Lab team labels May 18, 2026

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

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🔍 Code Review Update

Review of new commits: PR was rebased and expanded since last review.
Previously reviewed: b15d6235 | Now reviewing: 80838c00

Summary

The PR has been expanded from 5 to 6 commits, adding Fabric-accelerated get/set_local_poses:

  1. Service locator infrastructure on SimulationContext
  2. Service locator tests + changelog
  3. Indexed Fabric transform kernels in isaaclab.utils.warp.fabric
  4. FabricStageCache as a shared hierarchy handle
  5. (NEW) Merge commit to consolidate branches
  6. (NEW) FabricFrameView rewrite with get/set_local_poses + dirty tracking

✅ New Additions Since Last Review

  • Fabric-accelerated local poses: set_local_poses / get_local_poses now use wp.indexedfabricarray to read/write omni:fabric:localMatrix directly on the GPU
  • Bidirectional world↔local sync:
    • set_world_poses → recomputes localMatrix via _sync_local_from_world()
    • set_local_poses → marks _world_dirty, world recomputed on next get_world_poses
  • Per-view dirty tracking: _world_dirty flag is instance-scoped, so concurrent views on the same stage don't clear each other's flag
  • Parent matrix handling: _build_parent_indexed_array() + _compute_parent_fabric_indices() for parent world matrix lookups
  • Topology-adaptive: PrepareForReuse() calls + _rebuild_trans_ro_arrays() for automatic recovery
  • Comprehensive tests: 13 new integration tests covering local/world consistency, rotated/scaled parents, multi-view isolation

🔧 Remaining Observations

[Minor] Index array dtype mismatch still present

The kernels declare indices: ArrayUInt32, but _compute_fabric_indices() returns dtype=wp.int32:

# fabric_frame_view.py
return wp.array(indices, dtype=wp.int32, device=self._device)

Warp will silently cast, so this works in practice. Suggestion: switch to dtype=wp.uint32 for consistency with the kernel signatures. Not blocking.

[Minor] Undefined buffer references in get_local_poses

get_local_poses references self._fabric_local_translations_buf and self._fabric_local_orientations_buf:

if use_cached:
    translations_wp = self._fabric_local_translations_buf
    orientations_wp = self._fabric_local_orientations_buf

These don't appear to be initialized in _initialize_fabric(). Verify these buffers are created alongside the existing world-pose buffers.

📋 Architecture Notes

The world↔local propagation design is clean:

  • Write world → update local: _sync_local_from_world() runs update_indexed_local_matrix_from_world kernel immediately after world writes
  • Write local → lazy world update: _world_dirty flag defers update_indexed_world_matrix_from_local until the next world read

This asymmetry makes sense: world writes are typically followed by physics steps (which don't need locals), while local writes are often followed by world reads for rendering.

📋 Verdict

LGTM — the new local-pose acceleration is a significant feature addition. The bidirectional sync logic is well-designed, and the test coverage is comprehensive (33 test functions across all new modules). The minor dtype observation from the previous review remains, plus one potential undefined buffer issue to double-check.


Automated review by isaaclab-review-bot • Reviewed at 80838c00

@pv-nvidia pv-nvidia force-pushed the pv/fabric-local-poses branch 4 times, most recently from 80838c0 to 9ff3155 Compare May 20, 2026 14:11

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

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🔍 Code Review Update

Review of new commits: PR was rebased and expanded since last review.
Previously reviewed: eb5582ec | Now reviewing: 9ff3155

Summary

This PR delivers a well-architected feature: GPU-accelerated local-pose operations for FabricFrameView. The implementation is comprehensive and addresses the core limitation where local poses previously fell back to USD round-trips.

✅ Strengths

1. Clean Architecture

  • FabricStageCache provides shared hierarchy handles via the service locator pattern, avoiding per-view duplication
  • Three persistent selections (trans_sel_ro, world_sel_rw, local_sel_rw) cleanly separate read vs. write access patterns
  • Factory dispatch in FrameView._get_backend() correctly routes to UsdFrameView when Fabric is unavailable

2. Robust World↔Local Consistency

  • Bidirectional dirty tracking: set_local_poses marks _world_dirty, deferred until next world read
  • _sync_local_from_world() / _sync_world_from_local_if_dirty() keep matrices consistent
  • Per-view dirty flags prevent concurrent views from clearing each other's pending syncs

3. Topology-Adaptive Design

  • PrepareForReuse() + lazy array rebuild in _get_*_array() handles Fabric memory layout changes
  • _rebuild_trans_ro_arrays() consolidates index and indexed-array refresh

4. Excellent Test Coverage

  • 13+ new integration tests covering rotated parents, scaled parents, multi-view isolation
  • test_set_local_then_get_world_with_rotated_parent validates transpose-convention correctness
  • test_multi_view_per_view_dirty_isolation catches per-stage vs. per-view flag bugs

🔧 Minor Observations

[Minor] Index array dtype mismatch

_compute_fabric_indices() returns dtype=wp.int32, but kernels declare indices: ArrayUInt32:

return wp.array(indices, dtype=wp.int32, device=self._device)

Warp silently casts, so this works. Suggestion: use dtype=wp.uint32 for consistency with kernel signatures. Not blocking.

[Nit] Docstring transpose-convention note

The docstrings for update_indexed_local_matrix_from_world and update_indexed_world_matrix_from_local explain the transpose identity well. Consider adding a brief note that this relies on Fabric's row-major storage convention for future maintainers.

[Style] Empty sentinel shape

_fabric_empty_2d_array_sentinel uses shape (0, 0):

self._fabric_empty_2d_array_sentinel = wp.zeros((0, 0), dtype=wp.float32, device=self._device)

This is fine since the kernels gate on shape[0] > 0, but (0, 3) or (0, 4) might be slightly more self-documenting for unused position/quaternion slots.

📋 Architecture Notes

The asymmetric sync strategy is well-reasoned:

  • Write world → sync local immediately: _sync_local_from_world() runs right after world writes because downstream code (e.g., rendering) typically reads locals soon after
  • Write local → lazy world sync: _world_dirty flag defers the world = parent * local kernel until the next world read, avoiding unnecessary computation when multiple local writes occur before a world read

📋 CI Status

CI checks are currently pending. The pre-commit and changelog checks have passed.

📋 Verdict

LGTM — This is a significant feature addition that completes the Fabric acceleration story for FabricFrameView. The bidirectional sync logic is sound, test coverage is thorough, and the codebase is well-documented. The minor dtype observation is non-blocking.


Automated review by isaaclab-review-bot • Reviewed at 9ff31550


Update (d13ed99→7f1a012c): Reviewed large incremental batch (50+ files changed). This batch contains no changes to the core FabricFrameView implementation — the Fabric local-poses feature code is identical to the previously reviewed state.

Key changes in this batch (all outside the PR's core feature scope):

  1. isaaclab_ppisp made fully optional: All packages (isaaclab_physx, isaaclab_newton, isaaclab_ov, isaaclab_ovphysx) removed hard isaaclab_ppisp from dependencies. Lazy try/except ModuleNotFoundError with _raise_missing_ppisp_error() helper provides actionable install hints only when isp_cfg is actually set. Clean pattern, consistently applied.

  2. Cloner refactoring to ReplicateContext classes: physx_replicate, newton_physics_replicate, and ovphysx_replicate legacy functions now delegate to new PhysxReplicateContext, NewtonReplicateContext, and OvPhysxReplicateContext classes. Asset constructors call queue_*_replication(cfg) to register on REPLICATION_QUEUE. Well-structured — separates queueing from execution, enables batched replication.

  3. MJWarp ls_parallel deprecated: Config field emits DeprecationWarning via __post_init__(), _build_solver() ignores it. Removed from all test configurations.

  4. Newton manager lifecycle fix: close() now calls super().close() before cls.clear(), ensuring sensor invalidation callbacks fire while Newton state is still alive, preventing stale registrations leaking.

  5. OvPhysX/OVRTX runtime guards: import_ovphysx() helper with actionable install messages, ovphysx==0.4.13 pin.

  6. PhysxManager rigid body view: Now detects name collisions between rigid and non-rigid prims (e.g., JointWrenchSensor frame prim vs. rigid link with same name) and uses exact paths for ambiguous names.

  7. Version bumps and changelog consolidation: All changelog fragment files moved into proper versioned CHANGELOG.rst entries.

Previous inline comments status:

  • P1 (Missing wp.synchronize() in indexed getter paths): Still present — no changes to fabric_frame_view.py in this batch. Remains non-blocking per previous assessment.
  • P2 (Redundant kernel launch): Fixed in earlier commits (confirmed).

No new issues found in the incremental changes. All additions are well-implemented and follow established patterns. LGTM.


Automated incremental review by isaaclab-review-bot • Reviewed at 7f1a012c


Update (7f1a012→999cf3c6): Major architectural refactor reviewed.

Changes in this batch

The lazy dirty-flag mechanism (_DirtyFlag enum, _dirty field, _sync_*_if_dirty helpers, interleaved-write warning) has been removed entirely and replaced with a context-managed writer scope API (FrameViewSpaceWriterBase). This is a substantial and well-executed improvement:

  1. New xform_space_writer() context manager: Opens a scoped write session ("world" or "local"). On __exit__, derives the opposite-space matrices once via a single Warp kernel and calls wp.synchronize() once. Clean, predictable, no more subtle interleaving bugs.

  2. Single-active-writer invariant: Per-view lock prevents concurrent scopes — RuntimeError on double-entry. Well-tested.

  3. Hierarchy listener pause/restore: _FabricWriterMixin._enter_impl() pauses track_local_xform_changes / track_world_xform_changes during writes, restoring prior state on exit. Correctly handles pre-paused listeners (no accidental re-enable).

  4. Deprecated shims preserved: set_world_poses() / set_local_poses() remain as thin wrappers that open one-shot writer scopes internally + emit DeprecationWarning. Clean migration path.

  5. set_world_scales / set_local_scales removed (breaking): Since these were introduced in this release cycle without stable downstream users, removal without deprecation is appropriate. Changelog documents it.

  6. Test coverage: Comprehensive new tests for the writer contract — single-active invariant, derive-on-exit counting, empty-scope no-op, getter-raises-inside-scope, hierarchy tracking restore.

Previous comments status

  • P2 (Redundant kernel launch): Fixed — the _sync_fabric_from_usd_initial() path now only composes localMatrix then calls _recompute_world_from_local_all(). The redundant world compose is gone.
  • P1 (Missing wp.synchronize() in indexed getter paths): Still present in the non-cached decompose paths. Remains non-blocking per previous assessment (callers on the same CUDA stream see correct ordering; only cross-stream or immediate .numpy() usage is affected).
  • Minor observations (dtype, docstring, sentinel shape): These were non-blocking nits and remain unchanged. The sentinel shape (0, 0) is now less relevant since it is only used internally by the writer compose kernel.

New observations

No new issues found. The architectural shift from lazy dirty-flag tracking to eager derive-on-scope-exit is a clear improvement in correctness and readability. The _FabricWriterMixin pattern cleanly separates Fabric lifecycle management from the write logic. LGTM.


Automated incremental review by isaaclab-review-bot • Reviewed at 999cf3c6

@pv-nvidia

Copy link
Copy Markdown
Contributor Author

Superseded by the consolidated PR #5728 (pv/fabric-full-stack).

@pv-nvidia pv-nvidia closed this May 22, 2026
@pv-nvidia pv-nvidia reopened this May 22, 2026
@pv-nvidia pv-nvidia force-pushed the pv/fabric-local-poses branch 12 times, most recently from 4685420 to 6b56971 Compare May 25, 2026 17:24
@pv-nvidia pv-nvidia marked this pull request as ready for review May 25, 2026 18:05
pv-nvidia and others added 26 commits June 8, 2026 17:23
…ed MR

- Remove test_fabric_kernels.py: @wp.func math is fully exercised by
  the 57 integration tests in test_views_xform_prim_fabric.py
- Merge indexed-fabric-kernels.rst into fabric-local-poses.rst (single changelog)
- @wp.func helpers remain module-private (used by production kernels)
_local_from_world_transposed and _world_from_local_transposed were
one-line wrappers. Inline the math directly into the kernel bodies
(child_world * wp.inverse(parent_world) and child_local * parent_world)
to reduce indirection.
Introduce set_local_scales/get_local_scales and set_world_scales/
get_world_scales on BaseFrameView and all implementations:

- UsdFrameView: local scales read/write xformOp:scale; world scales
  decompose/compose from world transform matrix
- FabricFrameView: local scales operate on localMatrix (marks world
  dirty); world scales operate on worldMatrix (marks local dirty)
- NewtonSiteFrameView: both map to shape_scale (Newton treats scale
  as composed)
- OvPhysxFrameView: delegates to UsdFrameView

The deprecated set_scales/get_scales still work but emit
DeprecationWarning. USD/OvPhysX/Newton default to prior behavior;
Fabric defaults to world scales (matching its pre-existing semantics).
- Use row-major indexing (world_mtx[row][col]) instead of GetRow()
  which returns a Vec4 that can't be unpacked into Vec3d
- Cast numpy float32 to Python float for Gf.Vec3d constructor
- Replace internal get_scales() call with get_local_scales() in
  FabricFrameView._initialize_fabric to avoid deprecation warning
BaseFrameView.get_scales/set_scales are now concrete methods that emit
DeprecationWarning and delegate to _get_scales_default/_set_scales_default.
Subclasses that override them bypass the warning.

Remove the overrides from OvPhysxFrameView and NewtonSiteFrameView so
users get a consistent deprecation warning regardless of backend.
Move the OvPhysxFrameView notes into get_local_scales (the actual impl).
- Remove redundant child world matrix composition in
  _sync_fabric_from_usd_initial: the world matrix is immediately
  recomputed by _recompute_world_from_local() at the end of the method
  via child_world = child_local * parent_world. Eliminating the dead
  compose kernel saves one GPU kernel launch during initialization.

- Fix UsdFrameView.get_world_scales docstring: correctly describes
  extracting 'row lengths' (USD uses a row-vector convention where
  basis vectors are stored in rows), not 'column lengths'.

- Add pseudoroot check to UsdFrameView.set_world_scales: mirrors the
  guard in set_world_poses for consistency. The pseudoroot's identity
  transform means this is not a bug (parent_scale would be (1,1,1)
  regardless), but explicit guards prevent surprises with unusual
  stage structures.

- Document that FabricFrameView.get_local_scales and get_world_scales
  share the same pre-allocated buffer (_fabric_scales_buf). Callers
  interleaving both getters without copying will see overwritten values.
… shear warning

- Change get_local_scales/get_world_scales return type from wp.array to
  ProxyArray across all backends (BaseFrameView, UsdFrameView,
  FabricFrameView, NewtonSiteFrameView, OvPhysxFrameView).

- The deprecated get_scales() still returns wp.array (via .warp unwrap
  in _get_scales_default) to preserve backward compatibility.

- Add scale contract tests to frame_view_contract_utils.py:
  - test_local_scales_default_identity: verify (1,1,1) default
  - test_world_scales_default_identity: verify (1,1,1) default
  - test_set_local_scales_roundtrip: write/read consistency
  - test_set_world_scales_roundtrip: write/read consistency
  - test_local_scales_do_not_affect_local_poses: scale changes preserve T/R
  - test_scale_getters_return_proxyarray: type contract check

- Add shear/skew detection in FabricFrameView._sync_fabric_from_usd_initial:
  logs a one-time warning if any parent world transform has non-orthogonal
  rows (indicating shear), since TRS decomposition cannot represent shear.

- Document the shear limitation in BaseFrameView.get_world_scales docstring.

- Update existing Fabric scale tests to use .torch instead of
  torch.as_tensor (which would trigger ProxyArray deprecation bridge).

- Simplify _sync_fabric_from_usd_initial scale extraction to directly
  unwrap ProxyArray.warp (no longer needs defensive hasattr check).
Base class docstrings should describe the abstract contract without
mentioning implementation specifics (Fabric dirty flags, USD xformOps,
etc.). Move those details to the respective subclass docstrings where
they belong.
- Rename _get_scales_default/_set_scales_default to
  _get_scales_impl/_set_scales_impl across all backends. The 'default'
  name leaked implementation reasoning into the interface.

- Emit the DeprecationWarning only once (class-level flag) instead of
  on every call. Avoids flooding logs when legacy code calls get_scales/
  set_scales in a tight loop.
The ThreeDWorld link removal was unrelated to this PR and caused a
rebase conflict. Revert to upstream's version.
…View

Replace all remaining references to the deprecated set_scales/get_scales
with the new explicit set_world_scales/get_world_scales (and local
variants) in comments, docstrings, and log messages.
…tions

The previous rebase accidentally included a complete rewrite of the
Newton file (from a different branch). Reset to upstream/develop and
add only the 6 scale methods required by the new BaseFrameView ABC.
…rent

Implemented new tests to validate the behavior of world and local scale conversions in a hierarchy with a scaled parent. The tests ensure that setting local scales correctly computes world scales and vice versa, addressing USD-specific scale math not covered by existing tests.
Restores PR isaac-sim#5728's three-selection layout (`_trans_sel_ro`,
`_world_sel_rw`, `_local_sel_rw`) with asymmetric Fabric access flags
on `worldMatrix` and `localMatrix`.  Those flags are what protect the
user's write from being clobbered by Kit's per-tick
`IFabricHierarchy.update_world_xforms`:

* On `set_world_poses` (via `_world_sel_rw`, `localMatrix=RO`), Fabric
  does not recompute world from local -- the user's worldMatrix write
  survives until the renderer reads it.
* On `set_local_poses` (via `_local_sel_rw`, `worldMatrix=RO`), Fabric
  recomputes world from the new local on the next tick -- the renderer
  reads the correct world.

A single combined `worldMatrix=RW, localMatrix=RW` selection (the
recent design on this branch) removed that protection.  Fabric saw
both attributes as user-authored and fell back to the hierarchy's
canonical direction (local -> world), recomputing world from a stale
local and silently overwriting the user's world write.  That was the
failure mode behind the
`test_output_equal_to_usdcamera` regression and any other Camera + RTX
path that drives world poses through Fabric.

With the RO/RW protection back in place, the eager world<->local
flushes introduced by commits "fix: flush Fabric world matrices after
local writes" and the follow-up "set_world_poses eager local sync" are
no longer needed and are removed.  The `change_block` context manager
and its companion helpers existed only to batch those eager flushes;
with the flushes gone, the API has nothing to defer and is removed
from both `BaseFrameView` and `FabricFrameView`.

Class docstring now spells out the load-bearing role of the RO/RW
layout so a future refactor doesn't reintroduce the single-selection
shape.

Tests:

* Removed `test_set_local_*_updates_renderer_facing_fabric_world_matrix`
  (asserted an eager-update contract that the lazy design deliberately
  does not hold; correctness across the next render tick is provided
  by the RO/RW protection, not by an extra Warp kernel).
* Removed the four `test_change_block_*` tests; the API is gone.
* Inverted `test_interleaved_set_emits_no_warning` back to
  `test_interleaved_set_emits_warning`, restored `_dirty == LOCAL`
  assertions in `test_world_scales_roundtrip` and the symmetric
  `WORLD` assertion in `test_local_scales_roundtrip`, and updated
  `test_multi_view_per_view_dirty_isolation` to expect the lazy
  cross-view behavior.
* Adapted `test_prepare_for_reuse_detects_topology_change` and
  `test_fabric_rebuild_after_topology_change` to poll/rebuild all
  three selections.

Verified:

* `pytest test_ray_caster_camera.py::test_output_equal_to_usdcamera` passes.
* `pytest test_ray_caster_camera.py::test_output_equal_to_usd_camera_when_intrinsics_set` 4/4 pass.
* `pytest test_views_xform_prim_fabric.py` 71 passed, 3 skipped (cuda:1).
* `./isaaclab.sh -f` clean.

Net diff -198 lines.
@pv-nvidia pv-nvidia force-pushed the pv/fabric-local-poses branch from d13ed99 to 7f1a012 Compare June 8, 2026 17:29
Replaces the four FrameView pose/scale setters with a single
context-managed writer scope on every backend.  The writer batches
multiple writes (poses + scales) inside one scope, derives the
opposite-space matrix once on ``__exit__``, and synchronizes once.
Only one writer scope may be active per view at a time; view-level
getters raise ``RuntimeError`` while a writer scope is active.

API summary:

  with view.xform_space_writer("world") as w:
      w.set_poses(positions=p, orientations=o)
      w.set_scales(scales=s)
  # Derived (local) matrices are recomputed, the scope releases.

Public classes (in ``isaaclab.sim.views``):

  * ``FrameViewSpaceWriterBase``  -- abstract base
  * ``FrameViewWorldSpaceWriter`` -- world-space tag class
  * ``FrameViewLocalSpaceWriter`` -- local-space tag class

Behind the scenes:

  * ``BaseFrameView`` gains ``xform_space_writer()``,
    ``_active_writer``, and the abstract factory hooks
    ``_make_world_space_writer`` / ``_make_local_space_writer``.
    Public getters become guarded wrappers around new
    ``_get_*_impl`` backend hooks; they raise ``RuntimeError`` when a
    writer scope is active.
  * ``FabricFrameView`` ships ``_FabricWorldSpaceWriter`` and
    ``_FabricLocalSpaceWriter`` that pause
    ``IFabricHierarchy.track_local_xform_changes`` /
    ``track_world_xform_changes`` for the scope's lifetime (saving
    and restoring the prior state so we never re-enable a listener
    the caller had paused).  Eager dual-write inside the scope means
    Kit's per-tick ``updateWorldXforms`` does not redundantly
    recompute matrices we just wrote.  The renderer's independent
    ``omni:fabric:worldMatrix`` listener still observes the writes.
    The lazy-dirty mechanism is gone: the ``_DirtyFlag`` enum,
    ``_dirty`` field, ``_warned_interleaved_set`` field, the
    ``_sync_*_if_dirty`` helpers, and the one-time
    "interleaved set_world_poses / set_local_poses" warning are all
    deleted.  The three-selection RO/RW layout is kept as a
    defensive layer and for clarity of authoring intent.
  * ``UsdFrameView`` / ``NewtonSiteFrameView`` /
    ``OvPhysxFrameView`` ship pass-through writers (their
    ``set_poses`` / ``set_scales`` immediately delegate to the
    backend's ``_apply_*_write`` helpers; ``__exit__`` is a no-op
    beyond releasing the single-writer lock).

Setter deprecation / removal:

  * ``set_world_poses`` and ``set_local_poses`` are kept as
    one-time-warning shims on ``BaseFrameView`` that route through
    the writer internally.  Use ``view.xform_space_writer("world" |
    "local")`` and ``w.set_poses(...)``.
  * ``set_world_scales`` and ``set_local_scales`` were introduced in
    this release cycle without external users and are removed
    outright (no deprecation).  Use ``w.set_scales(...)`` inside a
    writer scope.
  * The existing ``set_scales`` deprecation shim is kept and now
    opens the backend-appropriate writer scope internally
    (Fabric: world, USD/OvPhysx: local).

Migration:

  All 81 call sites across ``source/``, ``scripts/``, and the test
  suites are migrated to the new API in this commit so the repo's
  own code base raises no deprecation warnings.  External callers
  on ``set_world_poses`` / ``set_local_poses`` / ``set_scales``
  keep working (one warning per class on first call).

Verification:

  * ``pytest source/isaaclab_physx/test/sim/test_views_xform_prim_fabric.py``
    -- 81 passed, 3 skipped (cuda:1 multi-GPU).
  * ``pytest source/isaaclab/test/sensors/test_ray_caster_camera.py::test_output_equal_to_usdcamera``
    -- the original Camera + RTX regression that motivated this
    arc, passes.
  * ``pytest source/isaaclab/test/sensors/test_ray_caster_camera.py::test_output_equal_to_usd_camera_when_intrinsics_set``
    -- 4 parametrizations pass.
  * ``./isaaclab.sh -f`` -- clean.

New test coverage for the writer contract (in
``test_views_xform_prim_fabric.py``):

  * world / local writer derives opposite space on exit
  * exactly one derive-kernel launch per scope (monkeypatched
    counter) regardless of how many set_poses / set_scales calls
    are made inside the scope
  * single-active-writer invariant raises ``RuntimeError``
  * exit restores prior ``track_local_xform_changes`` /
    ``track_world_xform_changes`` state (does not re-enable
    listeners the caller had paused)
  * invalid space string raises ``ValueError``
  * empty scope does not launch the derive kernel
  * view-level getters raise inside an active scope
@pv-nvidia pv-nvidia requested a review from xyao-nv as a code owner June 9, 2026 19:29
@github-actions github-actions Bot added the isaac-mimic Related to Isaac Mimic team label Jun 9, 2026
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

documentation Improvements or additions to documentation isaac-lab Related to Isaac Lab team isaac-mimic Related to Isaac Mimic team

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant