Add Newton physics preset for Anymal-D rough terrain#5096
Add Newton physics preset for Anymal-D rough terrain#5096hujc7 wants to merge 1 commit intoisaac-sim:developfrom
Conversation
Add RoughPhysicsCfg preset enabling rough terrain locomotion on Newton. Key solver settings: pyramidal friction cone (elliptic diverges in float32 with many mesh contacts), Newton collision pipeline, increased buffer sizes for mesh terrain contacts. - Add RoughPhysicsCfg(PresetCfg) with Newton solver config - Disable RayCaster height scanner for Newton (requires Kit) - Fix zero contact margin from USD import causing CCD divergence - Increase CollisionPipeline max_triangle_pairs for mesh terrain - Bump mujoco/mujoco-warp to 3.6.0, pin Newton to 141baffff9 Tested with: conda run -n env_isaaclab_develop python scripts/reinforcement_learning/rsl_rl/train.py --task Isaac-Velocity-Rough-Anymal-D-v0 --num_envs 4096 --max_iterations 300 --headless presets=newton Result: zero NaN, reward 13.33, episode length 957, 14 min.
Greptile SummaryThis PR adds a Newton physics preset ( Key changes:
Confidence Score: 5/5
Important Files Changed
Sequence DiagramsequenceDiagram
participant CLI as train.py CLI
participant HydraPreset as Hydra/PresetCfg
participant EnvCfg as AnymalDRoughEnvCfg
participant NM as NewtonManager
participant CP as CollisionPipeline
CLI->>HydraPreset: presets=newton
HydraPreset->>EnvCfg: resolve RoughPhysicsCfg → NewtonCfg<br/>(pyramidal, use_mujoco_contacts=False)
HydraPreset->>EnvCfg: scene.height_scanner = None
HydraPreset->>EnvCfg: observations.policy.height_scan = None
EnvCfg->>NM: start_simulation()
NM->>NM: WAR: fix zero margin<br/>(shape_margin[i]==0 → 0.01)
NM->>NM: ModelBuilder.finalize()
EnvCfg->>NM: initialize_solver() [use_mujoco_contacts=False]
NM->>CP: CollisionPipeline(model, broad_phase="explicit",<br/>max_triangle_pairs=2_000_000)
CP-->>NM: contacts()
loop Each simulation step
NM->>CP: generate contacts (mesh terrain)
CP-->>NM: contact data
NM->>NM: MJWarpSolver.step()<br/>(pyramidal cone, impratio=1.0)
end
Reviews (2): Last reviewed commit: "Add Newton physics preset for Anymal-D r..." | Re-trigger Greptile |
| "mujoco-warp==3.6.0", | ||
| "PyOpenGL-accelerate==3.1.10", | ||
| "newton==1.0.0", | ||
| "newton @ git+https://github.com/newton-physics/newton.git@141baffff9", |
There was a problem hiding this comment.
Short git commit hash for newton dependency
The newton package is pinned to a 9-character abbreviated SHA (141baffff9). Abbreviated hashes can theoretically collide as the repository grows, and some pip / dependency-resolution paths handle short hashes less reliably than full 40-character SHAs. The full hash should be used here for reproducibility and robustness.
| "newton @ git+https://github.com/newton-physics/newton.git@141baffff9", | |
| "newton @ git+https://github.com/newton-physics/newton.git@141baffff9ccab09bc07e3c4bff3c7e785acba4a", |
(Replace the long hash above with the actual full SHA; verify with git -C newton rev-parse 141baffff9.)
| cls._collision_pipeline = CollisionPipeline( | ||
| cls._model, broad_phase="explicit", max_triangle_pairs=2_000_000 | ||
| ) |
There was a problem hiding this comment.
Hardcoded max_triangle_pairs affects all collision-pipeline simulations
max_triangle_pairs=2_000_000 is now applied globally to every simulation that uses the Newton CollisionPipeline (i.e. any solver with use_mujoco_contacts=False, including flat-terrain and manipulation tasks). The default was 1M; this doubles the memory allocation for all such scenarios, not just mesh-terrain ones at 4096 envs.
Consider driving this from NewtonCfg (e.g. max_triangle_pairs: int = 1_000_000) so callers can opt in to the larger budget only when needed (as RoughPhysicsCfg would), rather than silently doubling memory overhead for every pipeline user.
| contact_margin = 0.01 | ||
| n_margin_fixed = 0 | ||
| for i in range(len(cls._builder.shape_margin)): | ||
| if cls._builder.shape_margin[i] == 0.0: | ||
| cls._builder.shape_margin[i] = contact_margin | ||
| n_margin_fixed += 1 | ||
| if n_margin_fixed > 0: | ||
| n_total = len(cls._builder.shape_margin) | ||
| logger.info(f"Set contact margin={contact_margin} on {n_margin_fixed}/{n_total} shapes with zero margin") |
There was a problem hiding this comment.
Global zero-margin fix applied to all Newton builds
The loop unconditionally patches every shape whose margin is exactly 0.0 across the entire model, including non-locomotion tasks (e.g. manipulation). For tasks where zero contact margin is intentional or where a different default is desirable, this silently changes behavior.
The comment in the removed line mentioned "manipulation examples" as the motivation for the old margin logic; applying 0.01 across the board may be too broad. At minimum, consider making the fallback value (and whether to apply it at all) configurable via NewtonCfg, similar to how max_triangle_pairs could be:
contact_margin = getattr(cfg, "default_contact_margin", 0.0)
if contact_margin > 0.0:
for i in range(len(cls._builder.shape_margin)):
if cls._builder.shape_margin[i] == 0.0:
cls._builder.shape_margin[i] = contact_margin
...This keeps the workaround available while letting tasks that don't need it (or prefer a different value) avoid the side-effect.
There was a problem hiding this comment.
🤖 Isaac Lab Review Bot — PR #5096
Summary
This PR adds a RoughPhysicsCfg Newton preset enabling the existing Isaac-Velocity-Rough-Anymal-D-v0 task to run with presets=newton. It includes three well-documented workarounds for upstream issues (zero contact margin, pyramidal cone for float32 stability, collision pipeline buffer overflow), version bumps for mujoco/mujoco-warp, and a Newton pin to a specific commit.
Files changed: 3 (newton_manager.py, setup.py, rough_env_cfg.py)
CI: ✅ labeler pass
Design Assessment
Well-structured. The PR correctly follows the established preset pattern used by the flat terrain config (flat_env_cfg.py). Specifically:
RoughPhysicsCfg(PresetCfg)mirrors the existingPhysicsCfg(PresetCfg)in flat_env_cfg withdefault/newton/physxattributes — consistent convention.- The
preset(default=..., newton=None)usage for disabling the height scanner on Newton matches how other backend-conditional features are handled. - The newton_manager.py changes are generic workarounds (zero margin fix, buffer sizing) that benefit all Newton users, not just this task — good placement in the shared manager.
- The solver parameters (
cone="pyramidal",impratio=1.0,use_mujoco_contacts=False,integrator="implicitfast") are each justified by the upstream issues documented in the PR description. - Comprehensive test results: zero NaN, strong reward convergence, multiple runs.
Findings
1. Hard-coded max_triangle_pairs doesn't scale with environment count (Medium)
File: newton_manager.py, _initialize_contacts
The collision pipeline is created with max_triangle_pairs=2_000_000, which is sized for ~4096 envs. However, _initialize_contacts is a shared path for all Newton users. If someone runs with 8192+ envs (or denser terrain meshes), they'll hit the same silent overflow bug.
Consider computing this from cls._num_envs or the model's triangle count:
# Example: scale based on envs, with headroom
tri_pairs = max(2_000_000, cls._num_envs * 500) if cls._num_envs else 2_000_000
cls._collision_pipeline = CollisionPipeline(
cls._model, broad_phase="explicit", max_triangle_pairs=tri_pairs
)Alternatively, if Newton exposes the actual triangle pair count after broad phase, that could auto-size it. Either way, the current value is a better default than 1M but will eventually be too small again.
2. Contact margin fix applies unconditionally to all Newton scenes (Low — Design Question)
File: newton_manager.py, start_simulation
The zero-margin → 0.01 fix runs for every Newton scene, not just rough terrain. For manipulation tasks where shapes intentionally have small/zero margins (e.g., tight finger grasps), forcing 0.01 could change contact behavior. The old comment even says "Set smaller contact margin for manipulation examples (default 10cm is too large)" — which this PR removes.
This is likely fine in practice (0.01 is small, and the original code wasn't setting margins either), but worth confirming that manipulation benchmarks (e.g. Allegro, Shadow hand) are not regressed. A targeted approach would be to only fix zero margins for mesh collision shapes, though that adds complexity.
3. Newton pinned to git commit hash — reproducibility concern (Low)
File: setup.py
"newton @ git+https://github.com/newton-physics/newton.git@141baffff9"This is appropriate for development/testing, but pinning to a commit hash means:
- No version metadata in the installed package (
pip show newtonwon't show a meaningful version) - pip won't cache it efficiently (rebuilds every install)
- If the newton repo is reorganized, the hash becomes un-fetchable
Is there a plan to tag a Newton release (e.g. 1.1.0) that includes the required fixes? If so, noting it as a TODO would help track it.
Verdict
Good PR. The preset is well-designed, follows established patterns, and the workarounds are individually justified with upstream references. The training results are solid. The findings above are suggestions for robustness — none are blocking.
|
Will be fixed by @ooctipus |
|
@greptileai Review |
Summary
Add
RoughPhysicsCfgNewton preset enabling Anymal-D rough terrain locomotion training with the Newton physics backend. This is a small, self-contained change that makes the existing stableIsaac-Velocity-Rough-Anymal-D-v0task runnable withpresets=newton.Changes:
RoughPhysicsCfg(PresetCfg)with Newton solver config tuned for mesh terrainomni.physics)CollisionPipelinemax_triangle_pairsto 2M for mesh terrainmujoco/mujoco-warpto 3.6.0, pin Newton to141baffff9Upstream issues and workarounds
Pyramidal cone for solver stability (WAR)
MuJoCo Warp uses float32 (vs float64 in MuJoCo C). The constraint solver diverges to NaN with elliptic cone + high impratio on mesh terrain contacts.
floatgoogle-deepmind/mujoco_warp#1000cone="pyramidal",impratio=1.0Zero contact margin from USD import (WAR)
Newton USD importer produces 100% of shapes with zero margin (225,281/225,281 at 4096 envs). Zero margin causes the CCD narrow phase to use a degenerate path where GJK fails to converge. Flat terrain is unaffected (plane geometry doesn't trigger this path); mesh terrain NaNs.
ModelBuilder.finalize()CollisionPipeline buffer overflow (WAR)
Default
max_triangle_pairs(1M) overflows with mesh terrain at 4096 envs (~2M triangle pairs). Overflow silently drops contacts, causing robots to fall through terrain.max_triangle_pairsto 2MRelated PRs
Test plan
Tested on single GPU with
env_isaaclab_developconda env:Newton backend confirmed via log:
Registered backend 'newton' for factory Articulation.presets=newton, zero NaN