Skip to content

[WIP][Rough Locomotion] Part 3: G1 on Newton (max_iterations 3000→5000, no physics tuning)#5312

Draft
hujc7 wants to merge 6 commits intoisaac-sim:developfrom
hujc7:jichuanh/g1-rough-terrain-wip
Draft

[WIP][Rough Locomotion] Part 3: G1 on Newton (max_iterations 3000→5000, no physics tuning)#5312
hujc7 wants to merge 6 commits intoisaac-sim:developfrom
hujc7:jichuanh/g1-rough-terrain-wip

Conversation

@hujc7
Copy link
Copy Markdown

@hujc7 hujc7 commented Apr 19, 2026

⚠️ WIP / draft

Tracking record for G1 rough-terrain on Newton. Single-line preset bump on max_iterations. Keep open until reviewed.

1. Summary

Enable G1 rough-terrain training on Newton. The only engine-specific change is a ~1.7× bump on max_iterations (Newton = 5000, PhysX = 3000). No physics, solver, reward, or action-space tuning — the G1 rough env config is identical on both backends.

2. Dependencies

  1. PR Add checked_apply helper for forwarding configclass fields onto upstream dataclasses #5365checked_apply helper.
  2. PR [Newton] Add Rough terrain locomotion Part 1: Foundation + quadrupeds on Newton #5248 — quadruped Newton support, shared RoughPhysicsCfg, NewtonShapeCfg(margin=0.01).
  3. PR [Rough Locomotion] Part 2: H1/Cassie bipeds on Newton #5298 — biped reset overrides (G1 inherits the position_range = (1.0, 1.0) from there).

3. Core finding — PhysX saturates at iter 3000; Newton matches by iter 5000

Ran both backends for 7500 iter on identical configs. Reward alone is misleading — PhysX reward oscillates +16 to +19 across its entire run past iter 3000 without improving. Episode length confirms the plateau:

iter PhysX reward PhysX ep_len Newton reward Newton ep_len
3000 +18.14 983 +6.21 979
4000 +19.38 986 +10.65 983
5000 +18.04 978 +16.01 984
5500 +18.19 983 +16.60 985
6000 +17.07 981 +18.86 996
6500 +16.71 989 +19.80 996
7000 +16.27 968 +18.10 976
7500 +15.81 +17.56 969
  • PhysX plateau: both metrics stable at iter 3000 (+18.14 / 983). No meaningful gain past iter 3000.
  • Newton at iter 5000: (+16.01 / 984) — matches PhysX quality on both reward and ep_len.
  • Newton at iter 6000+: equals or exceeds PhysX on both metrics.

Episode length > 960 everywhere means the robot is stable (not falling) even when reward is low — reward alone is not a sufficient convergence signal.

4. Ablation record

Tested at L40, 4096 envs, seed=42, Newton @ 381781c2 (1.2.0.dev0):

Variant iter Reward Verdict
A0 — Vanilla Newton 3000 +6.21 Newton slower but learning
A1 — Newton armature 0.01 3000 +5.14 No help
A2 — Newton armature 0.03 3000 +6.43 No help
D0 — Vanilla Newton (extended) 5000 +16.01 Matches PhysX plateau quality
E0 — Vanilla PhysX 3000 +18.14 PhysX plateau

Key observations:

  • Armature tuning (0.01, 0.03) does not change Newton's convergence rate on G1.
  • Damping preset (5 → 20) and finger-removal also tested in earlier rounds; no durable benefit once Newton is given enough iterations.
  • Newton catches PhysX by iter 5000 on vanilla config, so the framework-level max_iterations bump is sufficient on its own.

5. Change

source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/agents/rsl_rl_ppo_cfg.py:

from isaaclab_tasks.utils import preset

class G1RoughPPORunnerCfg(RslRlOnPolicyRunnerCfg):
    # Newton needs ~1.7x the PPO iterations to match PhysX on G1. PhysX saturates near iter 3000
    # (reward ≈ +18, ep_len ≈ 980) and does not meaningfully improve on either metric past that.
    # Newton reaches the same (reward, ep_len) quality at iter 5000 (+16 / 984). The gap is
    # sample-efficiency, not a ceiling — no physics or reward tuning closes it.
    max_iterations = preset(default=3000, newton=5000)

G1 rough_env_cfg.py is unchanged vs the parent bipeds branch — no finger removal, no armature preset, no damping preset.

Precedent for per-robot max_iterations tuning: Allegro Hand (5000), Spot (20000).

6. Versions

  • isaaclab_tasks 1.5.26 → 1.5.27

Type of change

  • New feature (non-breaking).

@github-actions github-actions Bot added documentation Improvements or additions to documentation isaac-mimic Related to Isaac Mimic team labels Apr 19, 2026
Copy link
Copy Markdown

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

Choose a reason for hiding this comment

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

PR #5312 Code Review: G1 Rough-Terrain Tuning (WIP) + FrameView + Newton Improvements

This PR contains three interconnected workstreams:

  1. G1 rough-terrain locomotion tuning (WIP) with Newton-specific armature/damping presets
  2. FrameView architecture refactoring to abstract backend-specific frame views
  3. Newton backend improvements including shape margin fixes and MDP warp compatibility

Overall Assessment: REQUEST_CHANGES

While this PR contains valuable architectural improvements, there are several issues that need addressing before merge.


🔴 Critical Issues

1. preset() Function Signature Ambiguity

File: source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py

The preset() function uses **kwargs with a magic default key, but this creates ambiguity when users want a preset named "default":

def preset(default=_MISSING, **kwargs):
    if default is _MISSING and "default" not in kwargs:
        raise ValueError("preset() requires 'default=' or a kwarg named 'default'")

Issue: The function allows both preset(default=X) and preset(newton=Y, default=X) but the semantics differ - in the first case default is positional, in the second it's a kwarg. This is confusing.

Recommendation: Use explicit dict construction: preset({"default": X, "newton": Y}) or require all keys be kwargs.

2. ScalarPreset Serialization Asymmetry

File: source/isaaclab_tasks/isaaclab_tasks/utils/hydra.py:46-73

The ScalarPreset class implements to_dict() but from_dict() would reconstruct a plain scalar, not a ScalarPreset. This breaks round-trip serialization:

sp = preset(default=0.01, newton=0.03)
d = sp.to_dict()  # Returns resolved scalar
# Cannot reconstruct ScalarPreset from d

Recommendation: Either document this limitation clearly or implement proper serialization.

3. Missing Type Annotations in New Termination Functions

File: source/isaaclab/isaaclab/envs/mdp/terminations.py:161-185

New functions body_lin_vel_out_of_limit and body_ang_vel_out_of_limit are missing return type annotations and have inconsistent docstring format:

def body_lin_vel_out_of_limit(
    env: ManagerBasedRLEnv,
    max_velocity: float,
    asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
) -> torch.Tensor:  # ✓ Has return type

Good - these are correct. But the docstrings lack Args/Returns sections that other functions in this file have.


🟡 Medium Issues

4. Hardcoded CHILD_OFFSET and ATOL Constants

File: source/isaaclab/isaaclab/sim/views/usd_frame_view.py:29-30

CHILD_OFFSET = (0.1, 0.0, 0.05)
ATOL = 1e-5

These magic constants lack documentation explaining their purpose:

  • Why 0.1, 0.0, 0.05 specifically for child offset?
  • Is ATOL=1e-5 appropriate for all use cases?

Recommendation: Add docstrings explaining these values' origins and when they might need adjustment.

5. RayCaster Major Refactoring Without Migration Path

File: source/isaaclab/isaaclab/sensors/ray_caster/ray_caster.py

The complete removal of _obtain_trackable_prim_view() (75+ lines) and switch to FrameView is a breaking change. The old code had specific handling for:

  • ArticulationView detection
  • RigidBodyView detection
  • XformPrimView fallback with warnings

Issue: The new FrameView abstraction assumes the backend handles this, but there's no deprecation warning or migration guide.

Recommendation: Add a CHANGELOG entry and migration notes for users relying on the old behavior.

6. feet_slide Body ID Slicing Hack

File: source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/mdp/rewards.py:87-88

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

Issue: This is a workaround for a Newton backend inconsistency, not a proper fix. The comment acknowledges Newton "reports duplicate body entries" - this should be fixed in Newton, not papered over in reward functions.

Recommendation: File a follow-up issue to fix Newton's body reporting. This workaround should be temporary.

7. G1 Action Space Comment Mismatch

File: source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py:35-36

# We need to include the joints above as well, to get the 37 DOF action space.
# This is less problematic since we can let the finger joints free-floating

The PR removes 14 finger joints from the action space (37 → 23 DOF), but the comment still references "37 DOF action space". This is stale documentation.


🟢 Minor Issues / Suggestions

8. Unused Import in interactive_scene.py

File: source/isaaclab/isaaclab/scene/interactive_scene.py

The PR removes several imports but the TYPE_CHECKING block imports DeformableObject and SurfaceGripper which may not be used if those backends aren't active.

9. Test Coverage for ScalarPreset

File: source/isaaclab_tasks/test/test_hydra.py

The test file is comprehensive (1200+ lines) but I don't see explicit tests for:

  • ScalarPreset with all-same-value presets (edge case)
  • preset() with invalid/empty kwargs
  • Round-trip serialization (which would catch issue #2)

10. torch.normtorch.linalg.norm Migration

Throughout rewards.py and terminations.py, the PR migrates from deprecated torch.norm to torch.linalg.norm. This is good practice, but should be noted in the PR description for searchability.


✅ Positive Observations

  1. FrameView Architecture: The BaseFrameViewFrameView → backend-specific implementations pattern is clean and follows good OOP principles.

  2. preset() Hydra Integration: The concept of backend-conditional values (preset(default=X, newton=Y)) is elegant for multi-backend configs.

  3. Newton Shape Margin Fix: The CHANGELOG entry for contact_marginmargin typo fix is well-documented.

  4. Test Infrastructure: The expanded test_hydra.py with 1200+ lines of tests shows good coverage of the new preset system.

  5. Warp Compatibility: The systematic wp.to_torch() wrapping in MDP functions enables Newton backend support.


Recommended Actions

  1. Clarify preset() function signature - consider explicit dict API
  2. Document magic constants in usd_frame_view.py
  3. Fix stale comment about 37 DOF in G1 config
  4. Add migration notes for RayCaster changes
  5. File follow-up issue for Newton duplicate body entries
  6. Add missing test cases for ScalarPreset edge cases

Reviewed at commit: a67b001

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🟡 Magic Constants: CHILD_OFFSET and ATOL lack documentation.

  • Why (0.1, 0.0, 0.05) for CHILD_OFFSET?
  • What is the origin of ATOL=1e-5?

Please add docstrings explaining these constants' purpose and when users might need to adjust them.

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🟡 Workaround for Newton Bug: The slicing asset_cfg.body_ids[:contacts.shape[1]] papers over a Newton backend issue.

The comment says Newton "reports duplicate body entries for closed-loop constraints" - this should be fixed in Newton itself, not worked around in reward functions.

Suggestion: File a follow-up issue to fix Newton's body reporting and mark this as a temporary workaround with a TODO.

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.

WIP PR Review: G1 Rough-Terrain Tuning

Reviewed the WIP commit a67b0017 which adds G1-specific rough terrain tuning on top of the parent PR #5298.

Summary

This is a well-documented WIP PR that addresses a real training issue (14 finger joints inflating action_rate_l2 penalty 3× vs H1) and applies the established Newton armature/damping preset pattern from Go2. The measured results (+20.54 PhysX, +9.61 Newton) demonstrate meaningful improvement.

Overall

For a WIP PR focused on recording tuning progress, this is clean and well-structured. The code follows established patterns (preset() for Newton-specific values, actuators["legs"] matching the G1_CFG definition). The detailed PR description with measured results is appreciated.

When promoting from WIP:

  • Consider whether the damping bump (5.0→20.0) is worth the base_contact regression noted in the PR description (7%→18.7%)
  • The armature-only variant (+8.10 reward) may be a cleaner landing point than armature+damping (+9.61 with contact regression)
  • As noted in the PR, this could potentially be split: fingers-out-of-action fix (clean PhysX improvement) could land independently of the Newton tuning work

No blocking issues found. The one inline comment is a minor documentation fix.

# terminations
self.terminations.base_contact.params["sensor_cfg"].body_names = "torso_link"

# G1 H1: remove finger joints from the action space. 14 finger joints contribute
Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Minor typo: "G1 H1" should be "G1" - H1 doesn't have finger joints (H1 only has legs, feet, and arms actuator groups).

Suggested change
# G1 H1: remove finger joints from the action space. 14 finger joints contribute
# G1: remove finger joints from the action space. 14 finger joints contribute

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🟡 Stale Documentation: Comments in this file reference "37 DOF action space" but this PR removes 14 finger joints, reducing the action space to 23 DOF.

Please update the comments to reflect the actual action space dimensions after finger joint removal.

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

🟡 Breaking Change: The complete removal of _obtain_trackable_prim_view() (75+ lines) is a significant refactoring.

The old code had specific handling for:

  • ArticulationView detection via UsdPhysics.ArticulationRootAPI
  • RigidBodyView detection via UsdPhysics.RigidBodyAPI
  • XformPrimView fallback with helpful warning messages

Please add a CHANGELOG entry and migration notes for users who may have been relying on the old behavior or its warning messages.

Copy link
Copy Markdown

Choose a reason for hiding this comment

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

Good Addition: The new body_lin_vel_out_of_limit and body_ang_vel_out_of_limit functions are useful safety checks that can prevent NaN propagation from solver singularities.

Minor suggestion: Consider adding Args/Returns sections to the docstrings for consistency with other functions in this file.

@hujc7 hujc7 force-pushed the jichuanh/g1-rough-terrain-wip branch from a67b001 to a4d0ebc Compare April 20, 2026 10:25
@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 hujc7 changed the title [WIP] G1 rough-terrain: fingers-out-of-action + Newton armature/damping tuning [WIP][Rough Locomotion] Part 3: G1 Newton fixes Apr 22, 2026
@hujc7 hujc7 force-pushed the jichuanh/g1-rough-terrain-wip branch from a4d0ebc to ccbd6f0 Compare April 22, 2026 19:19
@hujc7 hujc7 changed the title [WIP][Rough Locomotion] Part 3: G1 Newton fixes [WIP][Rough Locomotion] Part 3: G1 on Newton (2x iter budget, no physics tuning) Apr 22, 2026
@hujc7 hujc7 force-pushed the jichuanh/g1-rough-terrain-wip branch from ccbd6f0 to 99f50d7 Compare April 22, 2026 19:27
@hujc7 hujc7 changed the title [WIP][Rough Locomotion] Part 3: G1 on Newton (2x iter budget, no physics tuning) [WIP][Rough Locomotion] Part 3: G1 on Newton (max_iterations 3000→5000, no physics tuning) Apr 22, 2026
Copy link
Copy Markdown

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

Choose a reason for hiding this comment

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

🤖 Isaac Lab Review Bot

Summary

This PR (Part 3 of rough locomotion) adds Newton backend support for the G1 biped on rough terrain. The implementation is minimal and well-documented: a single preset(default=3000, newton=5000) on max_iterations in G1RoughPPORunnerCfg is the only G1-specific change. The PR description provides thorough ablation data showing Newton reaches PhysX-equivalent quality (reward ≈ +16, ep_len ≈ 984) at iter 5000 vs PhysX's plateau at iter 3000.

This is a clean, well-scoped change. The decision to bump iteration budget rather than tune physics/reward terms keeps the env config engine-agnostic, following precedent from Allegro Hand (5000 iter) and Spot (20000 iter).

Architecture Impact

No cross-module impact from the G1-specific changes. The max_iterations preset is localized to the PPO runner config. The rest of the PR stacks parent changes from #5298 (biped Newton support) and #5248 (quadruped Newton support), which have broader impact but were covered in prior reviews.

Implementation Verdict

Ship it — The G1-specific change (commit 99f50d7d) is correct and follows established patterns. The comment explains the rationale thoroughly.

Test Coverage

Acceptable for this change type. This is a hyperparameter tuning PR (iteration count), not a code behavior change. The existing rough-terrain training infrastructure provides implicit coverage. The PR description includes ablation data demonstrating the change achieves parity:

iter PhysX reward PhysX ep_len Newton reward Newton ep_len
3000 +18.14 983 +6.21 979
5000 +18.04 978 +16.01 984

The data validates the 5000 iteration preset is sufficient for Newton to match PhysX plateau quality.

CI Status

Only labeler check is present (passed ✅). No pre-commit/lint/test failures detected.

Branch Status

⚠️ This branch has diverged from develop (30 commits behind, 29 ahead). Consider rebasing before merge to pick up recent changes and ensure CI runs against current develop.

Findings

No new issues found in the G1-specific changes (commit 99f50d7d). The change is minimal, well-documented, and follows established patterns.

Prior review comments still applicable: The stacked commits from parent PRs have existing review comments (FrameView constants documentation, Newton body reporting workaround, etc.) that should be addressed in those parent PRs.


Reviewed at commit: 99f50d7

@hujc7
Copy link
Copy Markdown
Author

hujc7 commented Apr 24, 2026

@greptileai Review — please re-review. Force-pushed onto updated #5298 base (rebase only; no content change in this PR's own commit). Stack: #5365#5248#5298#5312.

@greptile-apps
Copy link
Copy Markdown
Contributor

greptile-apps Bot commented Apr 24, 2026

Greptile Summary

This PR is broader than its WIP title suggests: it delivers the checked_apply utility (PR #5365), NewtonShapeCfg with margin support (PR #5248), a major refactoring of all rough-terrain locomotion configs to a single shared RoughPhysicsCfg / EventsCfg base, and the headline G1 max_iterations preset (3000 → 5000 for Newton). The empirical convergence evidence in the PR description is thorough and the refactoring is clean.

  • The new body_lin_vel termination at 20 m/s is silently added to all rough-terrain envs; worth confirming the threshold doesn't clip lightweight robots (Go1, A1) under aggressive push or reset conditions.
  • Several Newton per-robot configs previously disabled push_robot; those overrides are now gone (behavioral change folded into the shared base).

Confidence Score: 5/5

Safe to merge; all remaining findings are P2 style/informational items that do not block correctness.

The core checked_apply utility is well-tested and the Newton shape config wiring is correct. The G1 max_iterations preset is the only engine-specific change and is backed by solid empirical data. The broad config refactoring appears intentional and the CHANGELOG captures all behavioral changes. No P0 or P1 issues found.

velocity_env_cfg.py — new body_lin_vel termination warrants a sanity check for lightweight quadrupeds under push events.

Important Files Changed

Filename Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py Major refactor: hoists shared RoughPhysicsCfg, moves startup events into base EventsCfg, adds body_lin_vel termination to all rough-terrain envs, and changes events: EventsCfg = MISSING → concrete default; broadly touches all robot training configs.
source/isaaclab/isaaclab/utils/configclass.py Adds checked_apply helper that forwards declared dataclass fields onto an external target, raising AttributeError on mismatch; import ordering has a minor style issue.
source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py Replaces hard-coded builder.default_shape_cfg.gap = 0.01 with checked_apply(shape_cfg, ...), correctly falling back to NewtonShapeCfg() defaults when no NewtonCfg is active.
source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py Introduces NewtonShapeCfg (margin, gap) and adds default_shape_cfg: NewtonShapeCfg field to NewtonCfg; well-documented defaults.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/agents/rsl_rl_ppo_cfg.py Core PR change: replaces max_iterations = 3000 with preset(default=3000, newton=5000) for G1 rough training, with well-documented empirical justification.
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/cassie/rough_env_cfg.py Removes per-backend event classes; adds Newton armature preset and asymmetric (1.0, 1.25) mass-distribution override; minor formatting artifact (double blank line inside post_init).
source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py Removes per-backend event classes and the Go2-specific PhysicsCfg (PhysX patch count is now preserved via the shared RoughPhysicsCfg); adds Newton armature preset.
source/isaaclab/test/utils/test_configclass.py Adds three well-structured tests for checked_apply: forwards all fields, raises on missing target field, and rejects non-dataclass src.
source/isaaclab_tasks/test/test_hydra.py Adds regression test verifying Go1 Newton armature preset resolves correctly to 0.02 without touching PhysX value.

Flowchart

%%{init: {'theme': 'neutral'}}%%
flowchart TD
    A["LocomotionVelocityRoughEnvCfg\n(sim: SimulationCfg(physics=RoughPhysicsCfg()))"]

    subgraph Physics["RoughPhysicsCfg (PresetCfg)"]
        P1["default/physx: PhysxCfg\n(gpu_max_rigid_patch_count=10x2^15)"]
        P2["newton: NewtonCfg\n(MJWarpSolverCfg + NewtonCollisionPipelineCfg\n+ NewtonShapeCfg(margin=0.01))"]
    end

    subgraph Events["EventsCfg (now shared base)"]
        E1["physics_material (startup)"]
        E2["add_base_mass (startup, log-uniform scale)"]
        E3["base_com (preset: PhysX=EventTerm, Newton=None)"]
        E4["push_robot (interval)"]
        E5["reset_base / reset_robot_joints (reset)"]
    end

    subgraph Terminations["TerminationsCfg"]
        T1["time_out"]
        T2["base_contact"]
        T3["body_lin_vel <= 20 m/s (NEW)"]
    end

    subgraph Robots["Per-robot overrides"]
        R1["G1: add_base_mass=None\nmax_iterations preset(3000->5000 Newton)"]
        R2["Cassie: mass_dist=(1.0,1.25), armature preset"]
        R3["H1: body_names=torso_link"]
        R4["Go1/Go2: armature preset(0->0.02 Newton)"]
        R5["Digit: explicit joint names"]
        R6["Anymal B/C/D: no overrides needed"]
    end

    subgraph CheckedApply["checked_apply"]
        CA["NewtonShapeCfg -> ModelBuilder.default_shape_cfg\nRaises AttributeError on field mismatch"]
    end

    A --> Physics
    A --> Events
    A --> Terminations
    A --> Robots
    P2 -->|create_builder| CA
Loading

Comments Outside Diff (3)

  1. source/isaaclab/isaaclab/utils/configclass.py, line 64 (link)

    P2 import dataclasses out of standard import position

    import dataclasses is inserted mid-block between from copy import deepcopy and from dataclasses import .... PEP 8 groups bare import X lines before from X import Y lines within the same stdlib section; placing it here breaks the existing convention in this file.

    Note: If this suggestion doesn't match your team's coding style, reply to this and let me know. I'll remember it for next time!

  2. source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/cassie/rough_env_cfg.py, line 708-711 (link)

    P2 Spurious double blank line inside __post_init__

    Two consecutive blank lines between statements inside a function body violate PEP 8 (double blank lines are reserved for top-level definitions). Looks like a merge artifact.

  3. source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py, line 29-30 (link)

    P2 Spurious double blank line after super().__post_init__()

    Same double-blank-line artifact as in cassie/rough_env_cfg.py; should be a single blank line inside the method body.

Reviews (1): Last reviewed commit: "Bump G1 max_iterations to 5000 on Newton..." | Re-trigger Greptile

Comment on lines 326 to 330
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.

P2 New body_lin_vel termination applies to every rough-terrain env

body_lin_vel_out_of_limit at 20 m/s is now a universal termination condition across all rough-terrain robots (Anymal, Go1/2, A1, H1, Cassie, Digit, G1). While 20 m/s is a generous safety cap and the intent (catching simulation explosions) is good, this is an additive behavioral change for all existing environments that wasn't present before. If any robot canonically reaches near that speed during certain reset conditions or in edge-case terrain interactions, the episode will silently terminate differently than before — worth verifying the threshold is safe for the lightest/fastest robots (Go1, A1) under aggressive push events.

…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/g1-rough-terrain-wip branch 2 times, most recently from 0ae2221 to 1660543 Compare April 24, 2026 06:23
@hujc7 hujc7 force-pushed the jichuanh/g1-rough-terrain-wip branch 2 times, most recently from b3bfb39 to 9e8f462 Compare April 24, 2026 06:27
ooctipus and others added 5 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
Restore per-biped overrides dropped by parent PR's consolidation:
- All bipeds (H1, Cassie, G1, Digit): restore
  reset_robot_joints.params["position_range"] = (1.0, 1.0). Bipeds
  have precise init poses that should not be randomly scaled on reset.
- Cassie: add leg armature=0.02 for stability on rough terrain.

Out of scope (pre-existing issues that fail on PhysX too):
- G1: finger joints dilute learning; addressed in follow-up PR.
- Digit: closed-loop kinematics fail in 7 steps on both backends.
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.
PhysX G1 saturates near iter 3000: reward ≈ +18, ep_len ≈ 980.
Past iter 3000 PhysX does not meaningfully improve on either metric —
reward oscillates +16-19 through iter 7500, ep_len stays flat.

Newton vanilla reaches matching (reward, ep_len) = (+16, 984) at
iter 5000 and equals/exceeds PhysX by iter 6000 (+18.9 / 996). The
gap is sample-efficiency, not a ceiling.

Ablation (armature 0.01/0.03, damping 5→20, finger-removal from action
space, Newton upstream a27277) did not change Newton's curve shape.
Use the framework preset on max_iterations rather than tuning physics
or reward terms, keeping the env config engine-agnostic. Precedent:
Allegro Hand (5000), Spot (20000).
@hujc7 hujc7 force-pushed the jichuanh/g1-rough-terrain-wip branch from 9e8f462 to 6aba4c0 Compare April 24, 2026 09:15
kellyguo11 added a commit that referenced this pull request Apr 26, 2026
…eam dataclasses (#5365)

# Description

Adds `isaaclab.utils.checked_apply` for forwarding the declared fields
of one dataclass onto another, raising `AttributeError` if the target is
missing a declared field.

The use case is Isaac Lab configclasses that mirror an upstream
library's dataclass (for example, 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 #5289 fixed for
`ShapeConfig.contact_margin` → `margin`). With `checked_apply`, the
failure surfaces at startup with a clear message instead of degrading
runtime behavior.

## API

```python
from isaaclab.utils import checked_apply

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

# at apply site (one line, no per-field setattr noise)
checked_apply(cfg.default_shape_cfg, builder.default_shape_cfg)
```

Internally:
1. Iterates `dataclasses.fields(src)` — single source of truth for
declared fields.
2. Raises `AttributeError` if `target` lacks a declared field.
3. Rejects non-dataclass `src` with `TypeError`.

## What's included

1. `source/isaaclab/isaaclab/utils/configclass.py` — `checked_apply`
function (lives next to `@configclass` since it operates on
dataclasses).
2. `source/isaaclab/isaaclab/utils/__init__.pyi` — export.
3. `source/isaaclab/test/utils/test_configclass.py` — three tests
(forwards all fields, raises on missing target field, rejects
non-dataclass src).
4. `source/isaaclab/docs/CHANGELOG.rst` — `4.6.13` entry.
5. `source/isaaclab/config/extension.toml` — version bump.

## Dependents

This PR is a dependency for the rough-terrain Newton stack:

1. PR #5248 — quadrupeds rough terrain, uses `checked_apply` to forward
`NewtonShapeCfg` onto Newton's upstream `ShapeConfig`. Without it,
`default_shape_cfg.margin` is left at Newton's upstream default of
`0.0`, breaking all non-Anymal-D robots on triangle-mesh terrain.
2. PR #5298 — bipeds (chains on #5248).
3. PR #5312 — G1 (chains on #5298).

## Type of change

- New feature (non-breaking).

## Checklist

- [x] Tests added (3 new in `test_configclass.py`)
- [x] Pre-commit checks pass
- [x] CHANGELOG + extension.toml bumped
- [x] No new dependencies

---------

Signed-off-by: Kelly Guo <kellyg@nvidia.com>
Co-authored-by: Kelly Guo <kellyg@nvidia.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

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

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants