Skip to content

[Exp] Cherry-pick warp MDP migration and capture safety from dev/newton#4945

Open
hujc7 wants to merge 6 commits intoisaac-sim:developfrom
hujc7:develop-manager-more-envs
Open

[Exp] Cherry-pick warp MDP migration and capture safety from dev/newton#4945
hujc7 wants to merge 6 commits intoisaac-sim:developfrom
hujc7:develop-manager-more-envs

Conversation

@hujc7
Copy link

@hujc7 hujc7 commented Mar 11, 2026

Summary

Changes included

  • Warp-first MDP terms (observations, rewards, events, terminations, actions) for manager-based envs
  • Tested warp env configs: Ant, Humanoid, Cartpole, locomotion velocity (A1, AnymalB/C/D, Cassie, G1, Go1/2, H1), Franka/UR10 reach
  • ManagerCallSwitch max_mode cap and scene capture config
  • MDP kernels made graph-capturable with consolidated test infrastructure
  • capture_unsafe safety guards on lazy-evaluated derived properties in articulation/rigid_object data
  • WrenchComposer fix: use fresh COM pose buffers instead of stale cached link poses

Dependencies

Must be merged after these PRs (in order):

  1. [Exp] Cherry-pick direct warp envs from dev/newton #4905
  2. [Exp] Cherry-pick manager-based warp env infrastructure from dev/newton #4829

Validated base

Validated against develop at 9720047.

Test plan

  • Run warp env training sweep across all new manager-based env configs
  • Run test_mdp_warp_parity.py and test_mdp_warp_parity_new_terms.py
  • Run test_action_warp_parity.py
  • Verify WrenchComposer COM pose is fresh (not stale) during graph replay

@github-actions github-actions bot added documentation Improvements or additions to documentation isaac-lab Related to Isaac Lab team labels Mar 11, 2026
@hujc7 hujc7 force-pushed the develop-manager-more-envs branch from f887335 to 0f63e21 Compare March 12, 2026 07:32
@hujc7
Copy link
Author

hujc7 commented Mar 12, 2026

@greptileai Review

@greptile-apps
Copy link
Contributor

greptile-apps bot commented Mar 12, 2026

Greptile Summary

This PR cherry-picks two large features from dev/newton onto develop: Warp-first MDP terms (observations, rewards, events, terminations, actions) for manager-based environments, and CUDA graph capture safety guards on lazily-evaluated derived properties in Newton articulation/rigid-object data.

Key changes:

  • New ManagerCallSwitch utility routes manager stage calls through STABLE / WARP_NOT_CAPTURED / WARP_CAPTURED paths, with JSON-env-var configuration and per-manager mode caps
  • @capture_unsafe decorator added to Tier-2 lazy properties in ArticulationData and RigidObjectData to produce clear RuntimeError instead of silent stale data during CUDA graph replay
  • Warp-first MDP kernels (observations.py, rewards.py, events.py, terminations.py, actions/joint_actions.py) bypass capture-unsafe Tier-2 properties by inlining rotations from Tier-1 root_link_pose_w / root_com_vel_w buffers directly
  • WrenchComposer fixed to use fresh body_com_pos_b / root_link_pose_w buffers instead of stale cached link poses
  • New state_kernels.py provides @wp.func helpers (rotate_vec_to_body_frame, body_lin_vel_from_root, body_ang_vel_from_root) used across MDP terms
  • Comprehensive warp-parity test infrastructure added (test_mdp_warp_parity.py, etc.)
  • _joint_pos_limit_normalized_kernel in observations.py performs an unguarded division by (upper - lower), which is zero for any fixed or zero-range joint included in the subset, silently writing NaN/inf to the observation buffer
  • randomize_rigid_body_com caches COM bounds keyed only on asset_cfg.name; a changed com_range (e.g., curriculum annealing) is silently ignored

Confidence Score: 3/5

  • PR is generally well-structured but has two correctness bugs: a silent NaN/inf from division-by-zero in an observation kernel, and a stale COM randomization range when com_range changes.
  • The architecture and capture-safety work is sound and the test coverage is solid. However, the unguarded division in _joint_pos_limit_normalized_kernel can silently corrupt observations for any zero-range joint, and the randomize_rigid_body_com cache-key bug would silently misapply an old COM range if the config is ever changed (e.g., curriculum). Both are runtime-correctness issues that warrant fixes before merge into a training-critical path.
  • source/isaaclab_experimental/isaaclab_experimental/envs/mdp/observations.py (division-by-zero at line 265) and source/isaaclab_experimental/isaaclab_experimental/envs/mdp/events.py (stale COM cache at lines 80-84) need attention.

Important Files Changed

Filename Overview
source/isaaclab_experimental/isaaclab_experimental/utils/manager_call_switch.py New utility routing manager stage calls through STABLE / WARP_NOT_CAPTURED / WARP_CAPTURED paths, with JSON-configurable modes per manager and max-mode ceiling caps. Logic is sound; _wp_capture_or_launch correctly caches graph and result on first capture. Max-mode baking in _load_cfg is correct. Minor style: get_mode_for_manager uses next(iter(self.DEFAULT_CONFIG)) instead of the already-defined self.DEFAULT_KEY constant.
source/isaaclab_experimental/isaaclab_experimental/envs/mdp/observations.py New Warp-first observation terms; contains a division-by-zero in _joint_pos_limit_normalized_kernel (line 265) when soft_joint_pos_limits has zero range for any joint, silently producing NaN/inf in the output buffer.
source/isaaclab_experimental/isaaclab_experimental/envs/mdp/events.py New Warp-first event terms; randomize_rigid_body_com function-level cache (lines 80-84) keys only on asset_cfg.name, so a changed com_range (e.g. curriculum annealing) leaves cached COM bounds stale without invalidation.
source/isaaclab_experimental/isaaclab_experimental/envs/mdp/rewards.py New Warp-first reward terms; Tier-1 inline computation avoids capture-unsafe lazy properties correctly. track_lin_vel_xy_exp and track_ang_vel_z_exp cache command tensor as wp.from_torch zero-copy view — safe as long as command buffers are never reallocated, which is the expected pattern.
source/isaaclab_newton/isaaclab_newton/assets/articulation/articulation_data.py Adds @capture_unsafe guards on lazy-evaluated Tier-2 properties (root_link_vel_w, root_com_pose_w, body_link_vel_w, body_com_pose_w, projected_gravity_b, heading_w, root_link_lin_vel_b) with clear migration reason string. Change is correct and non-breaking for non-capture use.
source/isaaclab_newton/isaaclab_newton/assets/rigid_object/rigid_object_data.py Same capture-safety annotation pattern as articulation_data.py, applied to the matching Tier-2 properties on RigidObjectData. Correct and consistent.
source/isaaclab/isaaclab/utils/warp/utils.py New module providing resolve_1d_mask (ids/mask → Warp bool mask, capture-safe fast path) and capture_unsafe decorator (raises RuntimeError on property access during graph capture). Both are clean and well-documented; no issues found.
source/isaaclab/isaaclab/utils/wrench_composer.py WrenchComposer COM-pose fix: replaces stale cached body_link_pose_w with fresh body_com_pos_b / root_link_pose_w buffers. Stricter hasattr guard is intentional and correctly documented.

Sequence Diagram

sequenceDiagram
    participant Env as ManagerBasedEnvWarp
    participant MCS as ManagerCallSwitch
    participant SM as StableManager
    participant WM as WarpManager
    participant WG as WarpGraph

    Env->>MCS: call_stage(stage="RewardManager_compute", warp_call, stable_call)
    MCS->>MCS: get_mode_for_manager("RewardManager")
    alt STABLE (0)
        MCS->>SM: fn(*args, **kwargs)
        SM-->>MCS: result
    else WARP_NOT_CAPTURED (1)
        MCS->>WM: fn(*args, **kwargs)
        WM-->>MCS: result
    else WARP_CAPTURED (2)
        MCS->>MCS: _wp_capture_or_launch(stage, call)
        alt First call (no cached graph)
            MCS->>WG: wp.ScopedCapture()
            MCS->>WM: fn(*args, **kwargs) [during capture]
            WM-->>MCS: result (cached)
            MCS->>WG: capture.graph stored
        else Subsequent calls
            MCS->>WG: wp.capture_launch(graph)
        end
        MCS-->>Env: cached result
    end
    MCS->>MCS: output_fn(result) if provided
    MCS-->>Env: final output
Loading

Last reviewed commit: a9ece43

raise TypeError(f"Unsupported mask type: {type(mask)}")

# --- Fast path: all elements ---
if ids is None or (isinstance(ids, slice) and ids == slice(None)):
Copy link
Contributor

Choose a reason for hiding this comment

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

Dead code in fast-path condition

After the normalization at lines 257–259 (if isinstance(ids, slice) and ids == slice(None): ids = None), ids can never be slice(None) by the time execution reaches line 285. The second conjunct (isinstance(ids, slice) and ids == slice(None)) is therefore unreachable dead code.

Suggested change
if ids is None or (isinstance(ids, slice) and ids == slice(None)):
if ids is None:
return all_mask

Copy link
Author

Choose a reason for hiding this comment

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

Fixed — removed the entire function (dead code, no callers on this branch).

Comment on lines +75 to +77
complete = torch.zeros((N, *value.shape[1:]), dtype=torch.float32, device=device)
complete[ids] = value
return wp.from_torch(complete, dtype=dtype)
Copy link
Contributor

Choose a reason for hiding this comment

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

Hardcoded torch.float32 ignores caller-supplied dtype

The intermediate complete buffer is always created with dtype=torch.float32 (line 75) regardless of the dtype parameter. When wp.from_torch(complete, dtype=dtype) is called with a non-float32 Warp dtype (e.g. wp.float16 or wp.float64), Warp will reinterpret — not convert — the memory, silently producing garbage values. The same issue exists at line 123 in make_complete_data_from_torch_dual_index.

A minimal fix is to derive the torch dtype from the Warp dtype, or assert that dtype == wp.float32 when the allocation path is taken. For example:

torch_dtype = wp.dtype_to_torch(dtype)
complete = torch.zeros((N, *value.shape[1:]), dtype=torch_dtype, device=device)

Copy link
Author

Choose a reason for hiding this comment

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

Fixed — removed the entire function (dead code, no callers on this branch).

Comment on lines +21 to +22
with contextlib.suppress(ImportError):
from isaaclab_experimental.envs import DirectRLEnvWarp, ManagerBasedRLEnvWarp
Copy link
Contributor

Choose a reason for hiding this comment

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

contextlib.suppress inside TYPE_CHECKING leaves names undefined for type checkers

When isaaclab_experimental is not installed, the contextlib.suppress(ImportError) silently swallows the ImportError and leaves DirectRLEnvWarp and ManagerBasedRLEnvWarp as undefined names. Because the return type annotation of unwrapped (line 135) references these names unconditionally, type checkers (mypy, pyright) will emit a NameError / unresolved-reference error when running against an environment that does not have isaaclab_experimental installed.

The standard approach for optional dependencies under TYPE_CHECKING is to provide fallback type aliases:

if TYPE_CHECKING:
    try:
        from isaaclab_experimental.envs import DirectRLEnvWarp, ManagerBasedRLEnvWarp
    except ImportError:
        from typing import Any
        DirectRLEnvWarp = Any  # type: ignore[assignment,misc]
        ManagerBasedRLEnvWarp = Any  # type: ignore[assignment,misc]

The same pattern applies to source/isaaclab_rl/isaaclab_rl/rl_games/rl_games.py (lines 55–56) and source/isaaclab_rl/isaaclab_rl/sb3.py (lines 36–37).

Copy link
Author

Choose a reason for hiding this comment

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

Low priority — not fixing in this PR. The contextlib.suppress pattern is consistent with the other RL wrappers (rl_games, sb3, skrl).

@hujc7 hujc7 force-pushed the develop-manager-more-envs branch 2 times, most recently from 74b80a2 to 760951f Compare March 12, 2026 08:35
@hujc7
Copy link
Author

hujc7 commented Mar 12, 2026

@greptileai Review

Comment on lines 487 to +503

# compute COM pose from link pose and body-frame COM offset
com_pose = _com_pose_from_link(
body_link_pose_w[env_ids[tid_env], body_ids[tid_body]],
body_com_pos_b[env_ids[tid_env], body_ids[tid_body]],
)

# set the torques to the composed torque
if torques:
composed_torques_b[env_ids[tid_env], body_ids[tid_body]] = cast_torque_to_link_frame(
torques[tid_env, tid_body],
wp.transform_get_rotation(link_poses[env_ids[tid_env], body_ids[tid_body]]),
is_global,
composed_torques_b[env_ids[tid_env], body_ids[tid_body]] = cast_torque_to_com_frame(
torques[tid_env, tid_body], com_pose, is_global
)
# set the forces to the composed force, if the positions are provided, adds a torque to the composed torque
# from the force at that position.
if forces:
# set the forces to the composed force
composed_forces_b[env_ids[tid_env], body_ids[tid_body]] = cast_force_to_link_frame(
forces[tid_env, tid_body],
wp.transform_get_rotation(link_poses[env_ids[tid_env], body_ids[tid_body]]),
is_global,
composed_forces_b[env_ids[tid_env], body_ids[tid_body]] = cast_force_to_com_frame(
Copy link
Contributor

Choose a reason for hiding this comment

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

Explicit torques silently overwritten when forces + positions both provided

In set_forces_and_torques_at_position_index (and the corresponding _mask variant), when a caller passes both torques and forces + positions, the torque buffer is first set from the explicit input, then immediately overwritten (not accumulated) by the position cross-product:

# step 1 — sets the torque
if torques:
    composed_torques_b[...] = cast_torque_to_com_frame(torques[...], ...)

# step 2 — silently overwrites step 1
if forces:
    if positions:
        composed_torques_b[...] = wp.cross(...)   # ← clobbers step 1

The net result is that explicitly provided torques are dropped when forces-at-position are also specified. Presumably the combined torque should be τ_explicit + r × F. The same overwrite existed in the original wp.skew() @ … version (pre-existing), but the refactoring is a good opportunity to fix it before this kernel is widely adopted. If the "last writer wins" semantics are intentional, it should be documented prominently.

Suggested fix for the set_ variant:

if forces:
    composed_forces_b[env_ids[tid_env], body_ids[tid_body]] = cast_force_to_com_frame(
        forces[tid_env, tid_body], com_pose, is_global
    )
    if positions:
        composed_torques_b[env_ids[tid_env], body_ids[tid_body]] += wp.cross(
            cast_to_com_frame(positions[tid_env, tid_body], com_pose, is_global),
            cast_force_to_com_frame(forces[tid_env, tid_body], com_pose, is_global),
        )

The same fix applies to set_forces_and_torques_at_position_mask.

Copy link
Author

Choose a reason for hiding this comment

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

Pre-existing behavior — not introduced by this PR. Added a NOTE comment to both set_* variants documenting the overwrite caveat. No caller currently passes both torques and forces+positions.

Comment on lines +52 to +58
# world poses since nothing triggers the lazy recomputation. Instead, we keep the two
# Tier 1 inputs (body_link_pose_w and body_com_pos_b) and let the wrench kernels
# compute the COM pose inline. This is both correct in eager mode and CUDA-graph-
# capture safe (Tier 1 buffers are stable sim-bind pointers updated by the solver).
data = self._asset.data
if hasattr(data, "body_link_pose_w") and hasattr(data, "body_com_pos_b"):
self._body_link_pose_w = data.body_link_pose_w
Copy link
Contributor

Choose a reason for hiding this comment

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

Breaking change: stricter asset compatibility check

The guard was widened from hasattr(data, "body_link_pose_w") to hasattr(data, "body_link_pose_w") and hasattr(data, "body_com_pos_b"). Any custom or third-party asset class that exposes body_link_pose_w but not body_com_pos_b will now silently fall through to the else branch and raise ValueError("Unsupported asset type: …") instead of working as before.

Since body_com_pos_b is required by the kernels, this restriction is correct. However it is an undocumented breaking change from the caller's perspective. At minimum the ValueError message should mention the missing attribute:

Suggested change
# world poses since nothing triggers the lazy recomputation. Instead, we keep the two
# Tier 1 inputs (body_link_pose_w and body_com_pos_b) and let the wrench kernels
# compute the COM pose inline. This is both correct in eager mode and CUDA-graph-
# capture safe (Tier 1 buffers are stable sim-bind pointers updated by the solver).
data = self._asset.data
if hasattr(data, "body_link_pose_w") and hasattr(data, "body_com_pos_b"):
self._body_link_pose_w = data.body_link_pose_w
if hasattr(data, "body_link_pose_w") and hasattr(data, "body_com_pos_b"):
self._body_link_pose_w = data.body_link_pose_w
self._body_com_pos_b = data.body_com_pos_b
elif hasattr(data, "body_link_pose_w"):
raise ValueError(
f"Asset type '{self._asset.__class__.__name__}' has 'body_link_pose_w' but is missing"
" 'body_com_pos_b'. Both Tier-1 buffers are required by WrenchComposer."
)
else:
raise ValueError(f"Unsupported asset type: {self._asset.__class__.__name__}")

Copy link
Author

Choose a reason for hiding this comment

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

Intentional — both buffers needed for correct COM pose. Old code cached stale Tier 2 property. All IsaacLab asset types expose both.

Copy link
Collaborator

@AntoineRichard AntoineRichard left a comment

Choose a reason for hiding this comment

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

It looks mostly safe to merge. Thanks a lot @hujc7 !

Copy link
Collaborator

Choose a reason for hiding this comment

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

Remove? :D

Copy link
Author

Choose a reason for hiding this comment

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

Already removed in PR #4905 — imports from stable now.

Copy link
Collaborator

Choose a reason for hiding this comment

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

Remove? :D

Copy link
Author

Choose a reason for hiding this comment

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

Not a duplicate — warp-specific decorator for func(env, out) -> None obs terms. Stable expects func(env) -> Tensor. Descriptor dataclass reused from stable.

Copy link
Collaborator

Choose a reason for hiding this comment

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

This is still outputing forces in the body frame? If yes all good :)

Copy link
Author

Choose a reason for hiding this comment

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

Yes, body frame. The only change is computing COM pose inline from Tier 1 buffers (body_link_pose_w + body_com_pos_b) instead of caching the Tier 2 body_com_pose_w property. No change to output frame or kernel logic.

@hujc7 hujc7 force-pushed the develop-manager-more-envs branch 2 times, most recently from 71388dd to 8bdb13f Compare March 12, 2026 23:45
@hujc7
Copy link
Author

hujc7 commented Mar 12, 2026

@greptileai Review

Comment on lines +230 to +240
if not hasattr(push_by_setting_velocity, "_scratch_vel"):
push_by_setting_velocity._scratch_vel = wp.zeros((env.num_envs,), dtype=wp.spatial_vectorf, device=env.device)
r = [velocity_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z", "roll", "pitch", "yaw"]]
push_by_setting_velocity._lin_lo = wp.vec3f(r[0][0], r[1][0], r[2][0])
push_by_setting_velocity._lin_hi = wp.vec3f(r[0][1], r[1][1], r[2][1])
push_by_setting_velocity._ang_lo = wp.vec3f(r[3][0], r[4][0], r[5][0])
push_by_setting_velocity._ang_hi = wp.vec3f(r[3][1], r[4][1], r[5][1])

wp.launch(
kernel=_push_by_setting_velocity_kernel,
dim=env.num_envs,
Copy link
Contributor

Choose a reason for hiding this comment

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

Function-level scratch buffers unsafe with varying num_envs

Multiple event functions (push_by_setting_velocity, reset_root_state_uniform, reset_joints_by_offset, reset_joints_by_scale, apply_external_force_torque) use if not hasattr(func, "_scratch_...") to lazily allocate scratch buffers as function-level attributes on their first call. This pattern has two failure modes:

  1. Larger second environment: If the function is first called with num_envs=64 (storing _scratch_vel of shape (64,)), then called again in the same Python process with num_envs=128, hasattr returns True so the old 64-element buffer is reused. The kernel launch uses dim=128, so threads with tid >= 64 will read/write out-of-bounds on _scratch_vel.

  2. Test suite leakage: Because the attribute lives on the module-level function object, it persists across test cases. Subsequent tests with a different num_envs silently inherit stale buffers.

A safe alternative is to key the cache on both the function name and env.num_envs, or store buffers on the env object:

cache_key = f"_scratch_vel_{env.num_envs}"
if not hasattr(push_by_setting_velocity, cache_key):
    setattr(push_by_setting_velocity, cache_key,
            wp.zeros((env.num_envs,), dtype=wp.spatial_vectorf, device=env.device))
scratch = getattr(push_by_setting_velocity, cache_key)

The same issue appears at lines ~77 (randomize_rigid_body_com), ~151 (apply_external_force_torque), ~340 (reset_root_state_uniform), ~460 (reset_joints_by_offset), and ~530 (reset_joints_by_scale).

Copy link
Author

Choose a reason for hiding this comment

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

Stale review — scratch buffer pattern was removed in latest push.

Comment on lines +138 to +144
def wrap_to_pi(angle: float) -> float:
"""Wrap input angle (in radians) to the range [-pi, pi)."""
two_pi = 2.0 * wp.pi
wrapped_angle = angle + wp.pi
# NOTE: Use floor-based remainder semantics to match torch's `%` for negative inputs.
wrapped_angle = wrapped_angle - wp.floor(wrapped_angle / two_pi) * two_pi
return wp.where((wrapped_angle == 0) and (angle > 0), wp.pi, wrapped_angle - wp.pi)
Copy link
Contributor

Choose a reason for hiding this comment

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

wrap_to_pi returns for input , contradicting the docstring

The docstring documents the output range as [-π, π) (half-open, π excluded). However, the edge-case guard on line 144 explicitly returns wp.pi when wrapped_angle == 0 and angle > 0, which fires for any positive odd multiple of π (e.g. angle = π, , …). Callers comparing output against the documented contract will see values of exactly in the output, which is outside [-π, π).

If the intent is to match PyTorch's atan2(sin(x), cos(x)) semantics for x = π (which yields ≈ π rather than due to sin(π) ≈ 1.2e-16), the docstring should say [-pi, pi] instead:

Suggested change
def wrap_to_pi(angle: float) -> float:
"""Wrap input angle (in radians) to the range [-pi, pi)."""
two_pi = 2.0 * wp.pi
wrapped_angle = angle + wp.pi
# NOTE: Use floor-based remainder semantics to match torch's `%` for negative inputs.
wrapped_angle = wrapped_angle - wp.floor(wrapped_angle / two_pi) * two_pi
return wp.where((wrapped_angle == 0) and (angle > 0), wp.pi, wrapped_angle - wp.pi)
"""Wrap input angle (in radians) to the range [-pi, pi]."""

Alternatively, if strict [-π, π) is required (e.g. to match torch.remainder-based wrapping), the edge-case guard should return -wp.pi instead of wp.pi.

Copy link
Author

Choose a reason for hiding this comment

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

Docstring was incorrect. Fixed to [-pi, pi] to match stable isaaclab.utils.math.wrap_to_pi convention. Fix is in PR #4829 where the function is introduced.

Comment on lines +107 to +108
assert asset_cfg.joint_mask is not None
assert asset.data.joint_pos.shape[1] == asset_cfg.joint_mask.shape[0]
Copy link
Contributor

Choose a reason for hiding this comment

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

assert is stripped by python -O (optimized mode)

assert statements are silently removed when Python is run with the -O / -OO optimisation flag (e.g. many CI runners and production launchers set PYTHONOPTIMIZE). If asset_cfg.joint_mask is None or the shapes mismatch, the kernel launch will raise an opaque Warp error rather than the descriptive message an explicit check would provide.

Suggested change
assert asset_cfg.joint_mask is not None
assert asset.data.joint_pos.shape[1] == asset_cfg.joint_mask.shape[0]
if asset_cfg.joint_mask is None:
raise RuntimeError(
f"joint_pos_out_of_manual_limit: 'asset_cfg.joint_mask' is None. "
"Call 'asset_cfg.resolve_for_warp(scene)' before invoking this term."
)
if asset.data.joint_pos.shape[1] != asset_cfg.joint_mask.shape[0]:
raise RuntimeError(
f"joint_pos_out_of_manual_limit: joint_pos dim 1 ({asset.data.joint_pos.shape[1]}) "
f"!= joint_mask size ({asset_cfg.joint_mask.shape[0]})."
)

Copy link
Author

Choose a reason for hiding this comment

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

Replaced with explicit raise ValueError in PR #4829 where these asserts are introduced.

@hujc7 hujc7 force-pushed the develop-manager-more-envs branch from 8bdb13f to 5713cea Compare March 13, 2026 07:44
@hujc7
Copy link
Author

hujc7 commented Mar 13, 2026

@greptileai Review

Comment on lines +95 to +99
i, j = wp.tid()
if joint_mask[j]:
v = joint_pos[i, j]
if v < lower or v > upper:
out[i] = True
Copy link
Contributor

Choose a reason for hiding this comment

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

Data race: concurrent non-atomic writes in 2D kernel

_joint_pos_out_of_manual_limit_kernel is launched with dim=(num_envs, num_joints), so multiple threads sharing the same i (env_id) but with different j (joint_id) can all execute out[i] = True concurrently. Per the CUDA programming model, concurrent non-atomic writes to the same address from different threads are undefined behaviour even when all writers store the same value.

In practice CUDA hardware serialises same-address stores within a warp and the value ends up correct, but this is not guaranteed across warps or thread-blocks. The safe alternatives are:

  1. Restructure as a 1D kernel (env_id) with an inner loop over joints (mirrors how _sum_sq_masked_kernel in rewards.py is written):
@wp.kernel
def _joint_pos_out_of_manual_limit_kernel(
    joint_pos: wp.array(dtype=wp.float32, ndim=2),
    joint_mask: wp.array(dtype=wp.bool),
    lower: float,
    upper: float,
    out: wp.array(dtype=wp.bool),
):
    i = wp.tid()
    for j in range(joint_pos.shape[1]):
        if joint_mask[j]:
            v = joint_pos[i, j]
            if v < lower or v > upper:
                out[i] = True
                return
  1. Keep the 2D layout but replace the plain store with a Warp atomic (e.g. a cast-to-int wp.atomic_or).

Copy link
Author

Choose a reason for hiding this comment

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

Acknowledged. All threads write the same value (True) to the same address — CUDA hardware serializes same-address stores within a warp and in practice this is safe even across warps for idempotent writes. Will restructure to a 1D kernel with inner loop in a follow-up for spec correctness.

@hujc7 hujc7 force-pushed the develop-manager-more-envs branch 3 times, most recently from 0cb897c to bacafb9 Compare March 14, 2026 21:25
@hujc7 hujc7 force-pushed the develop-manager-more-envs branch from bacafb9 to 4557de0 Compare March 14, 2026 21:38
@hujc7
Copy link
Author

hujc7 commented Mar 14, 2026

@greptileai Review

Comment on lines +395 to +440
def _reset_joints_by_scale_kernel(
env_mask: wp.array(dtype=wp.bool),
joint_ids: wp.array(dtype=wp.int32),
rng_state: wp.array(dtype=wp.uint32),
default_joint_pos: wp.array(dtype=wp.float32, ndim=2),
default_joint_vel: wp.array(dtype=wp.float32, ndim=2),
joint_pos: wp.array(dtype=wp.float32, ndim=2),
joint_vel: wp.array(dtype=wp.float32, ndim=2),
soft_joint_pos_limits: wp.array(dtype=wp.vec2f, ndim=2),
soft_joint_vel_limits: wp.array(dtype=wp.float32, ndim=2),
pos_lo: float,
pos_hi: float,
vel_lo: float,
vel_hi: float,
):
env_id = wp.tid()
if not env_mask[env_id]:
return

state = rng_state[env_id]
for joint_i in range(joint_ids.shape[0]):
joint_id = joint_ids[joint_i]

# scale samples in the provided ranges
pos_scale = wp.randf(state, pos_lo, pos_hi)
vel_scale = wp.randf(state, vel_lo, vel_hi)

pos = default_joint_pos[env_id, joint_id] * pos_scale
vel = default_joint_vel[env_id, joint_id] * vel_scale

lim = soft_joint_pos_limits[env_id, joint_id]
pos = wp.clamp(pos, lim.x, lim.y)
vmax = soft_joint_vel_limits[env_id, joint_id]
vel = wp.clamp(vel, -vmax, vmax)

# write into sim
joint_pos[env_id, joint_id] = pos
joint_vel[env_id, joint_id] = vel

rng_state[env_id] = state


# ---------------------------------------------------------------------------
# Reset joints by offset
# ---------------------------------------------------------------------------

Copy link
Contributor

Choose a reason for hiding this comment

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

Duplicate _reset_joints_by_scale_kernel — first definition is dead code

_reset_joints_by_scale_kernel is defined twice in this file: once here at line 395 (immediately before the _reset_joints_by_offset_kernel section) and again at line 541 (immediately before reset_joints_by_scale). The two bodies are byte-for-byte identical.

The first definition at line 395 is dead code: no callable in this file references it before it is shadowed by the second definition at line 541, which is the one actually used by reset_joints_by_scale. Python silently overwrites the name, so the function itself works correctly, but registering the same @wp.kernel-decorated name twice may trigger a duplicate-registration warning from Warp at module import time and will force Warp to JIT-compile the kernel twice.

The fix is to remove the first definition (lines 395–440) and its preceding section comment:

# ---------------------------------------------------------------------------
# Reset joints by scale          ← remove this block entirely
# ---------------------------------------------------------------------------


@wp.kernel
def _reset_joints_by_scale_kernel(   ← remove through line 440
    ...

The reset_joints_by_scale wrapper and the second kernel definition (lines 541 onward) should be left in place.

Copy link
Author

Choose a reason for hiding this comment

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

Done. Removed the dead first definition.

hujc7 added 6 commits March 15, 2026 00:34
Add experimental warp-compatible manager implementations, MDP terms,
utilities (buffers, modifiers, noise, warp kernels), ManagerCallSwitch
for eager/captured dispatch, and manager-based env orchestration.

Includes RL library wrapper updates (rsl_rl, rl_games, sb3, skrl) to
accept warp env types, and minor stable fixes (settings_manager
RuntimeError handling, observation_manager comment cleanup).
Add an experimental manager-based Cartpole environment using the warp
manager infrastructure as a reference task for testing and benchmarking.
Add warp-first MDP terms (observations, rewards, events, terminations,
actions) for manager-based envs. Update manager infrastructure with
ManagerCallSwitch max_mode cap, Scene capture config, body_ids_wp
resolution, and capture safety annotations.

Add newton state kernels for body-frame computations used by MDP terms.
Fix WrenchComposer to use Tier 1 sim-bind buffers (body_link_pose_w,
body_com_pos_b) instead of caching the lazy Tier 2 body_com_pose_w
property, which became stale after the first step.

Add capture_unsafe decorator for lazy-evaluated derived properties in
articulation and rigid object data. Update wrench kernels to compute
COM pose inline from link pose and body-frame COM offset.
Add manager-based warp env configs for classic (Ant, Humanoid),
locomotion velocity (A1, AnymalB/C/D, Cassie, G1, Go1/2, H1), and
manipulation reach (Franka, UR10). Include task-specific MDP terms
for humanoid observations/rewards and locomotion rewards/terminations/
curriculums.
Add parity test infrastructure and tests organized by MDP category:
observations, rewards, terminations, events, and actions. Tests verify
warp-first implementations match stable torch baselines across three
execution modes (stable, warp uncaptured, warp CUDA-graph captured).

Extract shared fixtures and mock objects to parity_helpers.py.
@hujc7 hujc7 force-pushed the develop-manager-more-envs branch from 4557de0 to a9ece43 Compare March 15, 2026 07:38
@hujc7
Copy link
Author

hujc7 commented Mar 15, 2026

@greptileai Review

lim = soft_joint_pos_limits[env_id, j]
lower = lim.x
upper = lim.y
out[env_id, k] = 2.0 * (pos - (lower + upper) * 0.5) / (upper - lower)
Copy link
Contributor

Choose a reason for hiding this comment

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

Division by zero for zero-range joints

When soft_joint_pos_limits has lower == upper for a joint (e.g., a fully-constrained or fixed joint included in the subset), (upper - lower) equals 0.0. In GPU code this produces ±inf or NaN silently rather than a crash, contaminating the entire observation buffer for affected environments.

The stable joint_pos_limit_normalized counterpart in isaaclab.envs.mdp.observations avoids this with a torch.where guard. A matching guard should be added here:

range_ = upper - lower
out[env_id, k] = wp.where(range_ > 0.0, 2.0 * (pos - (lower + upper) * 0.5) / (range_ + 1e-6), 0.0)

At minimum, a comment noting the caller's responsibility to exclude zero-range joints from asset_cfg would prevent silent numerical corruption.

Comment on lines +80 to +84
if not hasattr(fn, "_com_lo") or fn._asset_name != asset_cfg.name:
fn._asset_name = asset_cfg.name
r = [com_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z"]]
fn._com_lo = wp.vec3f(r[0][0], r[1][0], r[2][0])
fn._com_hi = wp.vec3f(r[0][1], r[1][1], r[2][1])
Copy link
Contributor

Choose a reason for hiding this comment

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

Cache stale when com_range changes across calls

The invalidation condition only checks fn._asset_name != asset_cfg.name, so if the same function is called with a different com_range for the same asset (e.g., curriculum-driven range annealing), the cached _com_lo / _com_hi vectors are never refreshed. The new range is silently ignored and the old range continues to be used for all subsequent randomization calls.

A minimal fix is to also include the range bounds as part of the cache key. For example, hashing or comparing the com_range dict alongside asset_cfg.name in the invalidation check would ensure the cached vectors are always consistent with the current configuration.

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

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants