Skip to content

[Rough Locomotion] Part 1: Foundation + quadrupeds on Newton (deps merged in)#5248

Open
hujc7 wants to merge 3 commits intoisaac-sim:developfrom
hujc7:jichuanh/rough-terrain-all-envs-pr
Open

[Rough Locomotion] Part 1: Foundation + quadrupeds on Newton (deps merged in)#5248
hujc7 wants to merge 3 commits intoisaac-sim:developfrom
hujc7:jichuanh/rough-terrain-all-envs-pr

Conversation

@hujc7
Copy link
Copy Markdown

@hujc7 hujc7 commented Apr 13, 2026

Description

Enables Newton rough-terrain locomotion training on all locomotion velocity envs (Go1, Go2, A1, Anymal-B/C/D, H1, Cassie, Digit, G1) on top of @ooctipus's Anymal-D foundation work, cherry-picked from PR #5225.

Why this PR exists

PR #5225 (Octi's draft) added Newton support for Anymal-D rough terrain. The other 9 locomotion envs were left out of scope. Octi is away and his PR has CI failures, so per maintainer guidance (Kelly Guo's comment) the required changes from #5225 are cherry-picked here so the rough-terrain stack can move forward without depending on his still-open WIP PR.

Dependencies

1. Cherry-pick from #5225 (614ea2dbb74)

Commit authored by Octi Zhang with Co-authored-by trailer. Subset of #5225 — what's kept and dropped:

# Item Status Reason
1 anymal_d/rough_env_cfg.py Anymal-D Newton config KEPT (then hoisted into shared parent in commit 2 below) Defines the Newton physics shape used for rough terrain
2 velocity_env_cfg.py — hoist physics_material, add_base_mass, base_com startup events into shared EventsCfg KEPT All envs need them
3 base_com guard preset(default=..., newton=None) KEPT Ablation A4 on #5225 (posted 2026-04-17): without the gate, 99.99% of episodes terminate from body_lin_vel runaway on Newton. Upstream Newton fix newton-physics/newton#2332 will let us drop the guard once it ships
4 velocity_env_cfg.pycollider_offsets startup event DROPPED (a) Greptile P1 on #5225: PhysX-only root_view methods, would AttributeError on Newton without a guard. (b) Ablation A3: clobbers the 1cm shape margin set by RoughPhysicsCfg (event resets gap = max(0, contact_offset − margin) = 0). Removing it gives +3.71 reward on Anymal-D Newton (+16.38 vs A0 baseline +12.47)
5 terminations.pybody_lin_vel_out_of_limit / body_ang_vel_out_of_limit + __init__.pyi exports DROPPED Were a NaN guard for the Newton body_lin_vel runaway when base_com was unguarded. With the preset(newton=None) gate (item 3), the runaway no longer occurs and the guards are unused
6 terrain_generator.py subdivided flat-grid border DROPPED Was a workaround for Newton triangle-collision failures on the box-primitive border. Newton has since improved triangle handling, so the workaround is no longer needed

2. New work — 2a532d1f745

2.1 NewtonShapeCfg + checked_apply wiring

The single most important Newton setting for rough terrain is shape margin. Without a nonzero margin, non-Anymal-D robots fail to learn stable contact on triangle-mesh terrain. The previous NewtonManager.create_builder only set gap = 0.01 and left margin at Newton's upstream default of 0.0.

This PR adds NewtonShapeCfg (the Isaac Lab wrapper) exposing margin and gap, and forwards it onto Newton's upstream ShapeConfig via checked_apply from PR #5365:

@configclass
class NewtonShapeCfg:
    margin: float = 0.0
    gap: float = 0.01

# in NewtonCfg
default_shape_cfg: NewtonShapeCfg = NewtonShapeCfg()

# in NewtonManager.create_builder
shape_cfg = cfg.default_shape_cfg if isinstance(cfg, NewtonCfg) else NewtonShapeCfg()
checked_apply(shape_cfg, builder.default_shape_cfg)

RoughPhysicsCfg opts in to default_shape_cfg=NewtonShapeCfg(margin=0.01).

2.2 Hoist RoughPhysicsCfg into shared base

Octi's per-env Anymal-D RoughPhysicsCfg (MJWarp solver + collision pipeline) is hoisted into LocomotionVelocityRoughEnvCfg.sim so every rough-terrain env inherits identical Newton physics. Per-env files become minimal robot-only deltas.

2.3 Per-env Newton-only tweak

  • Go1: leg armature preset for joint stability on lightweight quadruped.

2.4 Mass randomization rewrite

Replace EventsCfg.add_base_mass's additive (-5, 5) kg default with multiplicative (1/1.25, 1.25) log-uniform scale (operation="scale", distribution="log_uniform"). Scale-invariant across robot sizes, geometric mean 1.0, no per-robot kg overrides needed.

Versions

  • isaaclab_newton 0.5.21 → 0.5.22
  • isaaclab_tasks 1.5.24 → 1.5.25

Type of change

  • New feature (non-breaking).

Checklist

  • Pre-commit checks pass
  • CHANGELOG + extension.toml bumped on both isaaclab_newton and isaaclab_tasks
  • Co-author credit for @ooctipus on the cherry-pick commit
  • Ablation evidence cited in commit messages

@github-actions github-actions Bot added documentation Improvements or additions to documentation isaac-mimic Related to Isaac Mimic team labels Apr 13, 2026
@hujc7 hujc7 changed the title Enable all rough terrain envs on Newton backend [WIP]Enable all rough terrain envs on Newton backend Apr 13, 2026
@greptile-apps
Copy link
Copy Markdown
Contributor

greptile-apps Bot commented Apr 13, 2026

Greptile Summary

This PR hoists shared Newton rough-terrain physics (RoughPhysicsCfg, startup events, NewtonShapeCfg) into the base LocomotionVelocityRoughEnvCfg, simplifying all 9 per-robot configs from multi-class hierarchies into single __post_init__ overrides. It also introduces checked_apply to forward Isaac Lab wrapper fields onto upstream Newton objects with an API-drift guard.

  • P0 blocker: TerminationsCfg.body_lin_vel references mdp.body_lin_vel_out_of_limit (line 327 of velocity_env_cfg.py), a function that does not exist anywhere in the codebase. The PR description (item 5) explicitly states this function was dropped; its presence in TerminationsCfg is contradictory and will cause AttributeError on instantiation of every rough-terrain environment.

Confidence Score: 1/5

Not safe to merge — every rough-terrain env will crash on instantiation due to a missing MDP function.

A single P0 bug (mdp.body_lin_vel_out_of_limit does not exist) breaks all 10 environments at config-resolution time. Everything else in the PR — checked_apply, NewtonShapeCfg, RoughPhysicsCfg hoist, per-env simplifications — is clean and well-structured.

source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py (line 327) and source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/mdp/terminations.py (missing function definition).

Important Files Changed

Filename Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py Adds shared RoughPhysicsCfg preset, hoists startup events, and adds a body_lin_vel termination term — but the termination function mdp.body_lin_vel_out_of_limit does not exist, causing AttributeError on instantiation.
source/isaaclab/isaaclab/utils/configclass.py Adds checked_apply helper to forward dataclass fields onto an upstream object with an AttributeError guard; well-tested and correctly implemented.
source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py Adds NewtonShapeCfg (margin + gap) and wires it into NewtonCfg.default_shape_cfg; clean addition.
source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py create_builder now forwards NewtonShapeCfg onto builder.default_shape_cfg via checked_apply; falls back to wrapper defaults in non-Newton contexts.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py Simplified by removing per-env physics preset (now in shared base) and per-env EventsCfg subclasses; adds Newton armature preset for Go2.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py Removes DigitEventsCfg hierarchy; now mutates shared EventsCfg in post_init. Enables base_com randomization on PhysX path for Digit (previously disabled), which is a behavioral change vs other bipeds.
source/isaaclab_tasks/test/test_hydra.py Adds regression test for Go1 Newton armature preset; correct and clear.

Flowchart

%%{init: {'theme': 'neutral'}}%%
flowchart TD
    A[LocomotionVelocityRoughEnvCfg] --> B[sim: SimulationCfg\nphysics=RoughPhysicsCfg]
    A --> C[events: EventsCfg\nphysics_material\nadd_base_mass\nbase_com preset\nnewton=None]
    A --> D[terminations: TerminationsCfg\nbody_lin_vel ❌ missing fn]

    B --> E{preset resolve}
    E -- PhysX --> F[PhysxCfg\ngpu_max_rigid_patch_count]
    E -- Newton --> G[NewtonCfg\nMJWarpSolverCfg\nNewtonShapeCfg margin=0.01]

    G --> H[NewtonManager.create_builder]
    H --> I[checked_apply\nNewtonShapeCfg → builder.default_shape_cfg]

    A --> J[Per-robot subclass\n__post_init__ only]
    J --> K[Anymal B/C/D\nGo1/Go2/A1\nH1/G1/Cassie/Digit]
Loading

Reviews (3): Last reviewed commit: "Enable rough terrain on all locomotion e..." | Re-trigger Greptile

Comment on lines 22 to 38
class RoughPhysicsCfg(PresetCfg):
default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15)
newton = NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=200,
nconmax=100,
cone="pyramidal",
impratio=1.0,
integrator="implicitfast",
use_mujoco_contacts=False,
),
collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000),
num_substeps=1,
debug_mode=False,
)
physx = default

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 RoughPhysicsCfg duplicated across all 9 configs

The identical RoughPhysicsCfg class body is copy-pasted verbatim into every rough terrain config: anymal_b, anymal_c, anymal_d, a1, go1, go2, h1, g1, cassie, and digit. Changing Newton solver settings (e.g. raising njmax/nconmax for G1) will require editing 9+ files. Consider extracting this to a shared module (e.g. velocity_env_cfg.py or a new rough_physics_cfg.py) and importing it in each file.

Comment thread scripts/test_rough_envs_newton.sh Outdated
Comment on lines +54 to +61
if conda run -n env_isaaclab_develop python \
"${REPO_ROOT}/${TRAIN_SCRIPT}" \
--task "${TASK}" \
--num_envs "${NUM_ENVS}" \
--max_iterations "${MAX_ITERS}" \
--headless \
presets=newton \
> "${LOG_FILE}" 2>&1; then
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 Hardcoded conda environment name

conda run -n env_isaaclab_develop hardcodes the author's local environment name. Anyone else running this script needs to edit the file. Consider reading the name from an environment variable with a fallback, or using ./isaaclab.sh -p (the project's standard wrapper) as the invocation instead of a bare python call.

@hujc7 hujc7 changed the title [WIP]Enable all rough terrain envs on Newton backend Enable all rough terrain envs on Newton backend Apr 14, 2026
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from 710e99d to 293cadc Compare April 14, 2026 05:09
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 enables all rough terrain environments on the Newton backend by (1) adding RoughPhysicsCfg(PresetCfg) with shared Newton solver settings to 10 robot env configs, (2) merging the StartupEventsCfg into the base EventsCfg, (3) fixing base_com body name mismatches for non-base robots, and (4) adding body velocity terminations for NaN/explosion detection. It also includes the XformPrimView → FrameView refactoring from PR #5179 (new BaseFrameView ABC, UsdFrameView, FabricFrameView, NewtonSiteFrameView), ray caster sensor spawner improvements, and a terrain border mesh fix for Newton compatibility.

The approach is sound — unifying events into the base class and using presets for backend-specific behavior is the right direction. However, several Newton-specific event customizations were silently removed during the refactoring, which constitutes a behavioral change that should be documented.

Design Assessment

Design is sound, with one structural concern. The move from per-robot *NewtonEventsCfg / *PhysxEventsCfg / *EventsCfg(PresetCfg) classes to a unified EventsCfg with preset() fields and __post_init__ overrides is a significant simplification. The FrameView abstraction hierarchy (BaseFrameViewUsdFrameView / FabricFrameView / NewtonSiteFrameView with FrameView factory) is well-designed. The main structural concern is RoughPhysicsCfg being copy-pasted identically across 10 files — this should be defined once and imported.

Findings

🟡 Warning: RoughPhysicsCfg is duplicated identically across 10 env config filessource/isaaclab_tasks/.../config/*/rough_env_cfg.py

All 10 robot env configs define an identical RoughPhysicsCfg(PresetCfg) class with the same Newton solver parameters (njmax=200, nconmax=100, pyramidal, implicitfast, max_triangle_pairs=2_500_000). If any Newton parameter needs tuning, all 10 files must be updated in sync. Consider defining this once in velocity_env_cfg.py (or a shared module) and importing it. Robot-specific overrides (e.g., if G1 eventually needs higher njmax for its NaN issue) can still be done via __post_init__.

🟡 Warning: Newton-specific event customizations were silently removed — Multiple env config files

The old per-robot *NewtonEventsCfg classes contained Newton-specific overrides that are no longer present in the new code:

  1. push_robot = None was set for all 6 non-Anymal robots (A1, Go1, Go2, G1, H1, Cassie) on Newton. Now push_robot is active on Newton for all robots.
  2. reset_robot_joints.params["position_range"] = (1.0, 1.0) constrained joint resets to exact default positions on Newton. This override is now removed.
  3. reset_base.params zeroed out velocity randomization on Newton. This override is now removed.

These are intentional simplifications backed by the parity test results (6/7 envs show parity), but they change training dynamics on Newton. Recommend documenting these behavioral changes in the PR description so downstream users know the Newton event configuration has changed.

🟡 Warning: base_com randomization is newly enabled for several robots on PhysXvelocity_env_cfg.py:183

Previously, A1, Go1, Go2, Digit, Cassie, G1, and H1 all set base_com = None in their PhysX event configs (disabling COM randomization). The new code enables it for A1, Go1, Go2, and Digit (with corrected body names) and keeps it disabled for Cassie, G1, H1 (bipeds). This is a training-behavior change for the quadrupeds — the PR description mentions the anymal_c parity gap is related to this, but the change applies to other robots too. Worth noting in the PR description.

🟡 Warning: New collider_offsets startup event added to all rough terrain envsvelocity_env_cfg.py:199

A new randomize_rigid_body_collider_offsets startup event is added to the base EventsCfg with contact_offset_distribution_params=(0.01, 0.01). This event was not present in any of the old configurations. While the identical min/max suggests it applies a fixed offset (not truly random), this is a new event that affects all rough terrain environments. Should be mentioned in the PR description / changelog.

🔵 Suggestion: body_lin_vel_out_of_limit checks all bodies every stepvelocity_env_cfg.py:298

The new body_lin_vel termination uses body_names=".*" which checks the linear velocity of every body in the articulation every simulation step. For robots with many bodies (e.g., Digit with 30+ bodies), this computes a norm per body per env. While 20 m/s is a reasonable threshold for catching NaN/explosions, consider whether checking only a subset of bodies (e.g., the base body) would be sufficient and more performant. The NaN check is the most valuable part — an Inf/NaN in any body would propagate to the base anyway.

🔵 Suggestion: Terrain border mesh generation could be pre-validatedsource/isaaclab/isaaclab/terrains/terrain_generator.py

The new _add_terrain_border implementation using subdivided grid strips is a good fix for Newton collision detection with large triangles. However, when horizontal_scale is very small relative to border_width, this could generate a very large number of vertices ((border_width/hs + 1)^2 per strip). Consider adding a sanity check or logging a warning when the generated mesh exceeds a threshold vertex count.

Test Coverage

  • New code: The FrameView refactoring has good test coverage with test_frame_view_contract.py (359 lines), backend-specific tests for Newton and Fabric, and a ray caster regression test (test_raycaster_offset_does_not_affect_pos_w).
  • Env configs: The env config changes are tested via the author's parity test (7 envs × 2 backends × 300 iterations), documented in the PR description. No automated regression tests for env config behavioral changes, but this is consistent with the project's testing approach.
  • Gaps: The removed Newton event customizations (push_robot, reset params) and new events (collider_offsets, body_lin_vel) lack unit tests, but these are config-level changes exercised by integration tests.
  • Feature PR: Coverage adequate? Yes for the framework changes, Partial for the env config behavioral changes.

CI Status

Only a labeler check is visible and passing. No lint, build, or test CI results are shown — this may be expected for this repo's CI configuration or the checks may be running elsewhere.

Verdict

Minor fixes needed

The core approach — unifying events, adding Newton solver configs, and the FrameView abstraction — is well-executed with demonstrated parity results. The main concerns are:

  1. The 10× code duplication of RoughPhysicsCfg (easy to fix by extracting to a shared module)
  2. Silent behavioral changes from removed Newton event customizations should be documented
  3. New events (collider_offsets, body_lin_vel) should be mentioned in the PR description

None of these are blocking, but addressing them would make the PR cleaner and help downstream users understand what changed. The parity test results provide confidence that the changes work correctly at a training level.

class A1EventsCfg(PresetCfg):
default = A1PhysxEventsCfg()
newton = A1NewtonEventsCfg()
class RoughPhysicsCfg(PresetCfg):
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🟡 Warning: Duplicated RoughPhysicsCfg — This exact class is copy-pasted identically across all 10 robot env configs. Consider defining it once in a shared module (e.g., velocity_env_cfg.py) and importing it. This would make future Newton solver parameter changes a single-file edit.

newton=None,
)

collider_offsets = EventTerm(
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🟡 Warning: New event not present in old configs. collider_offsets is a new startup event added to all rough terrain environments. The identical min/max (0.01, 0.01) makes this a fixed offset rather than randomized. Was this intentional? If so, worth noting in the PR description as a behavioral change.

func=mdp.illegal_contact,
params={"sensor_cfg": SceneEntityCfg("contact_forces", body_names="base"), "threshold": 1.0},
)
body_lin_vel = DoneTerm(
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🔵 Suggestion: body_names=".*" checks every body in the articulation each step. For robots with many bodies this computes num_bodies × num_envs norms per step. Consider whether checking just the base body would be sufficient — NaN in any body will eventually propagate to the root state. The NaN detection is the most valuable part of this termination.

rewards: RewardsCfg = RewardsCfg()
terminations: TerminationsCfg = TerminationsCfg()
events: EventsCfg = MISSING
events: EventsCfg = EventsCfg()
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🔵 Note: Changed from events: EventsCfg = MISSING to events: EventsCfg = EventsCfg(). This means per-robot env configs no longer must provide events — they inherit the base class defaults. Good simplification, but means any robot that previously relied on MISSING to force explicit configuration will now silently get defaults.

@github-actions github-actions Bot added the asset New asset feature or request label Apr 14, 2026
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from 7c44bec to 2c9b667 Compare April 16, 2026 22:42
AntoineRichard added a commit that referenced this pull request Apr 17, 2026
## Summary

Fix incorrect attribute name `contact_margin` → `gap` on Newton
`ShapeConfig` in `NewtonManager.create_builder()`.

Newton PR #1732 renamed `contact_margin` to `gap` (broad-phase AABB
expansion). The IsaacLab code was never updated, creating a dead
attribute that Python silently accepted. The intended 1 cm default shape
gap was never applied.

## Newton PR #1732 rename mapping

| Old field | New field | Semantics |
|-----------|-----------|-----------|
| `thickness` | `margin` | Shape surface extension (affects contact
forces) |
| `contact_margin` | **`gap`** | Broad-phase AABB expansion (detection
range only) |
| `rigid_contact_margin` | `rigid_gap` | Builder-level default gap
(already 0.1) |

## Timeline

| Date | Newton | IsaacLab | `contact_margin` valid? |
|------|--------|----------|------------------------|
| Feb 19 | pin: `51ce35e` (has `contact_margin`) | #4646 adds
`contact_margin = 0.01` | Yes |
| Feb 24 | **PR #1732 renames `contact_margin` → `gap`** | — | — |
| Mar 2 | pin updated to `v0.2.3` (after rename) | #4761 keeps
`contact_margin` | **No — broken** |
| Mar 9 | — | #4883 removes the line | Removed |
| Apr 13 | — | #4822 re-adds `contact_margin` | **No — still broken** |

## Ablation: gap vs margin

We conducted an ablation study to understand the impact. Note: `margin`
(shape surface
extension) is a different field from `gap` (broad-phase range). The
original code intended
to set `gap`, but setting `margin` also has a significant positive
effect on training for
rough terrain locomotion.

| Setting | `gap` | `margin` | Go1 Reward (300 iter) | Effect |
|---------|-------|----------|----------------------|--------|
| Dead field (baseline) | 0.1 (default) | 0.0 | ~1.0 | — |
| `gap=0.01` only | 0.01 | 0.0 | 0.66 | No training improvement |
| `margin=0.01` only | 0.1 (default) | 0.01 | 18.77 | Major improvement
|
| `gap=0.01` + `margin=0.01` | 0.01 | 0.01 | 16.54 | Similar to
margin-only |

**This PR fixes the correct field migration** (`contact_margin` →
`gap`). The `margin` setting
for rough terrain contact quality will be addressed separately in the
rough terrain env PR
(#5248) via a new `default_shape_margin` config field on `NewtonCfg`.

## Test plan

- [x] Verified `contact_margin` is not a field on `ShapeConfig` (Newton
1.1.0.dev0)
- [x] Verified `gap` is the correct replacement field per Newton PR
#1732
- [x] Confirmed by camevor (Newton developer)
- [x] Ablation study: gap alone doesn't change training, so existing
tests should pass

Co-authored-by: Antoine RICHARD <antoiner@nvidia.com>
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from 775ab26 to fdd2cbd Compare April 18, 2026 10:28
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 — Updated Review

Summary

This PR enables all rough terrain locomotion environments on the Newton physics backend through:

  1. FrameView Abstraction — Major refactoring from XformPrimView to a backend-dispatching FrameView factory with implementations for USD, Fabric (PhysX), and Newton (GPU-resident site transforms via Warp kernels)
  2. NewtonCfg.default_shape_margin — New config field for per-env shape collision margin control
  3. Go1/Go2 armature presets — Newton-specific armature values (0.02) for training stability
  4. RayCaster improvements — Uses new FrameView for transform tracking, removes complex physics view detection
  5. Terrain border mesh fix — Subdivided grid mesh instead of large box primitives for Newton/MuJoCo collision compatibility
  6. New termination functionsbody_lin_vel_out_of_limit and body_ang_vel_out_of_limit for detecting solver singularities

Architecture Assessment

The FrameView design is excellent. The abstraction hierarchy is well-structured:

BaseFrameView (ABC)
├── UsdFrameView (USD XformCache backend)
├── FabricFrameView (Fabric GPU arrays, PhysX)  
└── NewtonSiteFrameView (Warp kernels, Newton GPU state)

FrameView (factory) ─→ selects backend at runtime

The factory pattern in FrameView.__new__ correctly dispatches to the appropriate backend based on the active physics manager. Contract tests in test_frame_view_contract.py ensure behavioral consistency across backends.

Detailed Findings

🟢 Excellent: Contract test suite

The test_frame_view_contract.py (359 lines) defines invariants that all backends must satisfy:

  • World pose = parent + local offset
  • Local pose stability after parent moves
  • World pose tracking when parent moves
  • Indexed get/set operations
  • Set/get roundtrip verification

This is the right approach for ensuring backend parity.

🟢 Good: RayCaster offset handling

The new test test_raycaster_offset_does_not_affect_pos_w explicitly validates that the sensor offset doesn't leak into data.pos_w. This catches a subtle bug that existed in the old implementation.

🟡 Warning: Backward compatibility alias may hide issues

# source/isaaclab/isaaclab/sim/views/xform_prim_view.py
XformPrimView = FrameView

While this preserves backward compatibility, it means:

  1. Existing code using XformPrimView will silently start using the new factory
  2. The API differs (FrameView returns wp.array, old XformPrimView returned torch.Tensor)
  3. Consider adding a deprecation warning via __getattr__ or similar

🟡 Warning: Newton site discovery depends on USD path matching

In NewtonSiteFrameView.__init__, sites are discovered via USD regex matching, then body indices are looked up by parsing the body name from the USD path. If the USD hierarchy doesn't match the Newton model body naming, this could fail silently:

# newton_site_frame_view.py line ~280
body_name = site_parent.GetName()
# ... 
if body_name in body_name_to_idx:
    ...
else:
    logger.warning(f"Body '{body_name}' not found in Newton model for site {site_path}")

The warning-only approach is appropriate for flexibility, but the site will be attached to the world frame (body_index=-1) which may not be the intended behavior. Consider whether this should raise an error in strict mode.

🟡 Warning: Terrain border memory consumption

The new subdivided grid border mesh generation creates (width/hs + 1) * (length/hs + 1) vertices per strip. For a typical config with border_width=20 and horizontal_scale=0.05:

vertices per strip ≈ (20/0.05 + 1) * (length/0.05 + 1) = 401 * length_factor

This is significantly more vertices than the old box approach but necessary for Newton collision compatibility. Consider adding a note about memory implications in the docstring.

🔵 Suggestion: _gather_scales kernel is O(N × M)

The _gather_scales kernel iterates through all shapes to find ones matching the body:

for s in range(num_shapes):
    if shape_body[s] == bid and found == 0:
        out_scales[i] = shape_scale[s]
        found = 1

For large models with many shapes, this is O(num_sites × num_shapes). Consider building a body→first_shape index map during initialization for O(1) lookups. This is a minor optimization but could matter for complex robots.

🔵 Suggestion: Document quaternion convention

The code uses (w, x, y, z) quaternion ordering in some places and (x, y, z, w) in others. While the Warp kernels correctly handle the conversion, explicit documentation of the expected convention at API boundaries would help:

def get_world_poses(self, ...) -> tuple[wp.array, wp.array]:
    """...
    Returns:
        orientations: Quaternions in (w, x, y, z) order.  # ← Add this
    """

Test Coverage Assessment

Component Tests Coverage
FrameView contract test_frame_view_contract.py ✅ Excellent
Newton backend Contract tests + newton-specific ✅ Good
Fabric backend Contract tests + fabric-specific ✅ Good
RayCaster integration test_raycaster_offset_does_not_affect_pos_w ✅ Good
Termination functions None visible ⚠️ Missing
Terrain border mesh None visible ⚠️ Missing

The new termination functions (body_lin_vel_out_of_limit, body_ang_vel_out_of_limit) should have unit tests verifying they correctly detect NaN velocities and threshold violations.

CI Status

Only labeler check visible and passing. Full CI suite (tests, lint) status unknown.

Verdict

Approve with minor suggestions

This is a well-designed PR that brings significant improvements:

  1. ✅ Clean abstraction layer for multi-backend transform queries
  2. ✅ Proper contract testing ensures backend parity
  3. ✅ Newton-specific fixes (shape margin, border mesh) address real collision issues
  4. ✅ Armature presets enable Newton rough terrain training

The warnings above are non-blocking observations for potential improvement. The code is production-ready.


Reviewed commit: fdd2cbd

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 — Additional Review

Critical Bug Found

The previous review approved this PR, but I've identified a critical bug that will crash at runtime.

🔴 Bug: feet_slide crashes when asset_cfg.body_ids is default slice(None)

The change on line 87 of rewards.py introduces a regression:

body_vel = wp.to_torch(asset.data.body_lin_vel_w)[:, asset_cfg.body_ids[:contacts.shape[1]], :2]

When asset_cfg uses the default body_ids = slice(None), this will crash with:

TypeError: 'slice' object is not subscriptable

Reproduction:

s = slice(None)
s[:5]  # TypeError: 'slice' object is not subscriptable

Root cause: The PR description mentions this handles "Newton's ball-joint rod bodies (Digit)" but the implementation doesn't handle the common case where body_ids is a slice.

Suggested fix: Convert the slice to indices first, or check the type:

if isinstance(asset_cfg.body_ids, slice):
    # slice(None) means all bodies, so use all up to contact count
    body_ids = list(range(contacts.shape[1]))
else:
    body_ids = asset_cfg.body_ids[:contacts.shape[1]]
body_vel = wp.to_torch(asset.data.body_lin_vel_w)[:, body_ids, :2]

Verdict

Request Changes — The feet_slide bug will crash any locomotion env using the default asset_cfg for this reward. This must be fixed before merge.


Reviewed commit: fdd2cbd


body_vel = wp.to_torch(asset.data.body_lin_vel_w)[:, asset_cfg.body_ids, :2]
# Use sensor body count to slice asset velocities — ensures matching dimensions
# even when Newton reports duplicate body entries for closed-loop constraints.
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🔴 Bug: slice object is not subscriptable

When asset_cfg uses the default body_ids = slice(None), this line crashes with TypeError: 'slice' object is not subscriptable.

>>> slice(None)[:5]
TypeError: 'slice' object is not subscriptable

The comment mentions handling Newton's duplicate body entries, but this breaks the common case where no explicit body_ids are configured.

Suggested fix:

Suggested change
# even when Newton reports duplicate body entries for closed-loop constraints.
# Use sensor body count to slice asset velocities — ensures matching dimensions
# even when Newton reports duplicate body entries for closed-loop constraints.
if isinstance(asset_cfg.body_ids, slice):
# Default slice(None) means all bodies — just take the first N matching sensor count
body_ids = slice(contacts.shape[1])
else:
body_ids = asset_cfg.body_ids[:contacts.shape[1]]
body_vel = wp.to_torch(asset.data.body_lin_vel_w)[:, body_ids, :2]

@kellyguo11 kellyguo11 moved this to In review in Isaac Lab Apr 20, 2026
@isaaclab-review-bot isaaclab-review-bot Bot dismissed their stale review April 21, 2026 16:17

Dismissing: bot incorrectly used CHANGES_REQUESTED. Bot policy is COMMENT-only — never APPROVE or REQUEST_CHANGES.

hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 22, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

## Ablation (Cassie, 1500-iter Newton, 4096 envs, seed 42)

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

## H1 (unchanged, 1500-iter Newton)

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from fa81247 to 60de194 Compare April 22, 2026 08:01
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 22, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

## Ablation (Cassie, 1500-iter Newton, 4096 envs, seed 42)

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

## H1 (unchanged, 1500-iter Newton)

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 22, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
@hujc7
Copy link
Copy Markdown
Author

hujc7 commented Apr 22, 2026

@greptileai Review — please re-review the latest commits (log-uniform mass randomization on #5248; biped H1/Cassie re-enable on #5298). Thanks.

@hujc7 hujc7 changed the title Enable all rough terrain envs on Newton backend [Rough Locomotion] Part 1: Quadrupeds on Newton Apr 22, 2026
# Digit uses "torso_base" as base body
self.events.add_base_mass.params["asset_cfg"].body_names = "torso_base"
self.events.base_external_force_torque.params["asset_cfg"].body_names = "torso_base"
self.events.base_com.default.params["asset_cfg"].body_names = "torso_base"
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 base_com silently enabled for Digit on PhysX

The old DigitPhysxEventsCfg.__post_init__ explicitly set self.base_com = None. This line now mutates .default of the preset (enabling base_com randomization on the PhysX path) instead of keeping it disabled. H1, G1, and Cassie all explicitly self.events.base_com = None in their new __post_init__; Digit is the only biped that does not.

Suggested change
self.events.base_com.default.params["asset_cfg"].body_names = "torso_base"
self.events.base_com = None

If enabling CoM randomization for Digit on PhysX is intentional, a comment explaining the rationale (and why it diverges from the other bipeds) would help reviewers.

Suggested change
self.events.base_com.default.params["asset_cfg"].body_names = "torso_base"
self.events.base_com = None

@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from 60de194 to 1442ceb Compare April 24, 2026 00:30
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 24, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
@github-actions github-actions Bot added the isaac-lab Related to Isaac Lab team label Apr 24, 2026
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from 1442ceb to 2a532d1 Compare April 24, 2026 04:10
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 24, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
@hujc7 hujc7 changed the title [Rough Locomotion] Part 1: Quadrupeds on Newton [Rough Locomotion] Part 1: Quadrupeds + bipeds + G1 on Newton (foundation + envs) Apr 24, 2026
@hujc7 hujc7 changed the title [Rough Locomotion] Part 1: Quadrupeds + bipeds + G1 on Newton (foundation + envs) [Rough Locomotion] Part 1: Foundation + quadrupeds on Newton (deps merged in) Apr 24, 2026
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from 2a532d1 to cf53a59 Compare April 24, 2026 06:03
@hujc7
Copy link
Copy Markdown
Author

hujc7 commented Apr 24, 2026

@greptileai Review — please re-review. Force-pushed onto the updated #5365 base (the checked_apply rename + AGENTS.md drop from that PR landed here automatically via rebase). No content change in this PR's own commits beyond the SHA shift. PR stack is now:

  1. Add checked_apply helper for forwarding configclass fields onto upstream dataclasses #5365checked_apply helper
  2. this PR ([Rough Locomotion] Part 1: Foundation + quadrupeds on Newton (deps merged in) #5248) — cherry-pick from Supports Anymal-D Rough terrain training in newton #5225 (subset, per ablation) + shared RoughPhysicsCfg + NewtonShapeCfg(margin=0.01)
  3. [Rough Locomotion] Part 2: H1/Cassie bipeds on Newton #5298 — bipeds (chains on this)
  4. [WIP][Rough Locomotion] Part 3: G1 on Newton (max_iterations 3000→5000, no physics tuning) #5312 — G1 (chains on [Rough Locomotion] Part 2: H1/Cassie bipeds on Newton #5298)

@isaaclab-review-bot please re-review.

hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 24, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
Comment on lines +325 to +329
)
body_lin_vel = DoneTerm(
func=mdp.body_lin_vel_out_of_limit,
params={"max_velocity": 20.0, "asset_cfg": SceneEntityCfg("robot", body_names=".*")},
)
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.

P0 mdp.body_lin_vel_out_of_limit does not exist — every env will crash on instantiation

TerminationsCfg.body_lin_vel calls mdp.body_lin_vel_out_of_limit, but that function is not defined anywhere in the codebase. The local terminations.py only contains terrain_out_of_bounds, and neither the core isaaclab.envs.mdp.terminations module nor the lazy_export()-driven mdp.__init__ exposes a body_lin_vel_out_of_limit symbol.

The PR description (item 5) explicitly says this function was dropped from #5225, yet the code adds a DoneTerm using it. Every LocomotionVelocityRoughEnvCfg subclass will raise AttributeError: module 'mdp' has no attribute 'body_lin_vel_out_of_limit' as soon as the config is resolved. Either define the function in the local terminations.py, import it from the correct module, or remove the body_lin_vel termination term.

…eam dataclasses

When an Isaac Lab configclass mirrors an upstream library's dataclass
(for example NewtonShapeCfg → Newton's ShapeConfig), bare setattr
loops are fragile: if upstream renames or removes a field, every
write becomes a silent no-op (the failure mode PR isaac-sim#5289 fixed for
ShapeConfig.contact_margin → margin).

Add isaaclab.utils.checked_apply(src, target):
  - Iterates fields(src) — single source of truth for declared fields
  - Raises AttributeError if target lacks a declared field — failure
    surfaces at startup, not at runtime
  - One-line apply at the call site, no per-field setattr noise
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from cf53a59 to e32f9d8 Compare April 24, 2026 06:17
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 24, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from e32f9d8 to 76767be Compare April 24, 2026 06:23
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 24, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 24, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
ooctipus and others added 2 commits April 24, 2026 09:14
Originally Octi's commit on PR isaac-sim#5225. Cherry-picked here so the rough
terrain stack does not depend on his still-open WIP PR while he is away.

Included from isaac-sim#5225:
- source/isaaclab_tasks/.../config/anymal_d/rough_env_cfg.py:
  Anymal-D SimulationCfg-based RoughPhysicsCfg (MJWarp solver + collision
  pipeline). The shared parent will hoist this in the next commit.
- source/isaaclab_tasks/.../velocity/velocity_env_cfg.py:
  Hoist physics_material, add_base_mass, base_com startup events into
  the shared EventsCfg. base_com guarded with preset(newton=None) per
  ablation A4 (without the gate, 99.99% of episodes terminate from
  body_lin_vel runaway on Newton). Upstream Newton fix
  newton-physics/newton#2332 will let us drop
  the gate once it ships in a release.

Dropped from isaac-sim#5225 (no longer needed):
- collider_offsets startup event in velocity_env_cfg.py: per ablation
  A3 (clobbers shape margin via gap = max(0, contact_offset - margin) =
  0, costing -3.71 reward on Anymal-D) and greptile P1 (PhysX-only
  root_view methods, raises AttributeError on Newton without a guard).
- body_lin_vel_out_of_limit / body_ang_vel_out_of_limit terminations
  and their __init__.pyi exports: were a NaN guard for the Newton
  body_lin_vel runaway when base_com was unguarded. With the
  preset(newton=None) gate on base_com, the runaway no longer occurs
  and the guards are unused.
- terrain_generator.py subdivided flat-grid border: was a workaround
  for Newton triangle-collision failures on the box-primitive border.
  Newton has since improved triangle handling, so the workaround is no
  longer needed.

Co-authored-by: Octi Zhang <zhengyuz@nvidia.com>
Adds:
1. NewtonShapeCfg wrapper exposing per-shape collision defaults
   (margin, gap) via NewtonCfg.default_shape_cfg. NewtonManager.
   create_builder forwards it onto Newton's upstream
   ModelBuilder.default_shape_cfg via isaaclab.utils.checked_apply
   (PR isaac-sim#5365). Replaces the hardcoded gap=0.01 line with a single
   typed wrapper — the previous code never set margin, leaving it
   at Newton's upstream default of 0.0 and breaking all non-Anymal-D
   robots on triangle-mesh terrain.

2. Hoists Octi's per-env Anymal-D RoughPhysicsCfg into the shared
   LocomotionVelocityRoughEnvCfg so every rough-terrain env
   (Go1, Go2, A1, Anymal-B/C, H1, Cassie, Digit, G1) inherits
   identical Newton physics. The shared preset opts in to
   default_shape_cfg=NewtonShapeCfg(margin=0.01).

3. Per-env Newton-only tweaks where ablation showed measurable
   gains:
   - Go1: leg armature preset for joint stability.

4. Replaces additive (-5, 5) kg default on EventsCfg.add_base_mass
   with multiplicative (1/1.25, 1.25) log-uniform scale —
   scale-invariant across robot sizes, geometric mean 1.0, no
   per-robot kg overrides needed.

- isaaclab_newton 0.5.21 -> 0.5.22
- isaaclab_tasks  1.5.24 -> 1.5.25
@hujc7 hujc7 force-pushed the jichuanh/rough-terrain-all-envs-pr branch from 76767be to 7ae07b7 Compare April 24, 2026 09:15
hujc7 added a commit to hujc7/IsaacLab that referenced this pull request Apr 24, 2026
Restore base-mass randomization on H1 and Cassie that was disabled with
add_base_mass = None in their rough-terrain configs (pre-existing biped
convention from 2024-06 PR isaac-sim#444, later reinforced by PR isaac-sim#4165's Newton NaN
TODO). The parent PR isaac-sim#5248 switches the shared default to log-uniform scale
(1/1.25, 1.25), which is safer for bipeds than the old additive (-5, 5) kg
(effectively ±25% on H1's torso vs ±100% on Cassie's pelvis).

- H1 inherits the shared default (symmetric ±25% scale, body_names="torso_link").
- Cassie overrides to (1.0, 1.25) asymmetric heavier-bias: lighter-than-
  nominal pelvis destabilizes Cassie's closed-loop Achilles rod coupling
  and hip PD response, while heavier-than-nominal dampens dynamics.

| Variant                        | reward | ep len | vs disabled |
|--------------------------------|-------:|-------:|------------:|
| None (disabled, prior default) |  23.93 |    910 |     1.00x   |
| (1/1.25, 1.25) sym25           |  14.15 |    850 |     0.59x x |
| (1/1.10, 1.10) tight10         |  14.53 |    831 |     0.61x x |
| **(1.0, 1.25) heavier25**      | **21.50** | **932** | **0.90x** |

Tightening the range symmetrically did not help (tight10 ~ sym25) — the
lighter side is what destabilizes, not the magnitude. Restricting to
[1.0, 1.25] (never lighter, up to +25% heavier) preserves most of the
randomization benefit while avoiding the failure mode. Episode length
also improves (932 vs 910), indicating the randomized policy is actively
more stable during episodes — the lower aggregate reward comes from extra
dof-torque regularizer paid to handle heavier instances, not degraded
task completion.

H1's larger base mass (≈15 kg torso) means ±25% on the default scale
(11-19 kg range) is well within the controller's robustness margin. H1
reward at iter 1499: 24.02 with mass rand on vs 23.58 with it disabled
(1.02x, essentially equal). Re-enabling provides sim-to-real robustness
at negligible training cost.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

asset New asset feature or request documentation Improvements or additions to documentation isaac-lab Related to Isaac Lab team isaac-mimic Related to Isaac Mimic team

Projects

Status: In review

Development

Successfully merging this pull request may close these issues.

3 participants