Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 21 additions & 2 deletions source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,21 @@ def start_simulation(cls) -> None:
device = PhysicsManager._device
logger.info(f"Finalizing model on device: {device}")
cls._builder.up_axis = Axis.from_string(cls._up_axis)
# Set smaller contact margin for manipulation examples (default 10cm is too large)

# WAR: USD import produces shapes with zero contact margin. Zero margin causes
# CCD to use the is_discrete path (epsilon=0), where GJK fails to converge on
# mesh terrain, producing NaN in body_q/joint_q.
# TODO: file upstream Newton issue for USD importer zero-margin default.
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")
Comment on lines +296 to +304
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 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.


with Timer(name="newton_finalize_builder", msg="Finalize builder took:"):
cls._model = cls._builder.finalize(device=device)
cls._model.set_gravity(cls._gravity_vector)
Expand Down Expand Up @@ -398,7 +412,12 @@ def _initialize_contacts(cls) -> None:
if cls._needs_collision_pipeline:
# Newton collision pipeline: create pipeline and generate contacts
if cls._collision_pipeline is None:
cls._collision_pipeline = CollisionPipeline(cls._model, broad_phase="explicit")
# WAR: default max_triangle_pairs (1M) overflows with mesh terrain at
# 4096+ envs (~2M triangle pairs). Overflow silently drops contacts.
# No upstream issue tracking auto-sizing yet.
cls._collision_pipeline = CollisionPipeline(
cls._model, broad_phase="explicit", max_triangle_pairs=2_000_000
)
Comment on lines +418 to +420
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 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.

if cls._contacts is None:
cls._contacts = cls._collision_pipeline.contacts()

Expand Down
6 changes: 3 additions & 3 deletions source/isaaclab_newton/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,10 @@ def run(self):
EXTRAS_REQUIRE = {
"all": [
"prettytable==3.3.0",
"mujoco==3.5.0",
"mujoco-warp==3.5.0.2",
"mujoco==3.6.0",
"mujoco-warp==3.6.0",
"PyOpenGL-accelerate==3.1.10",
"newton==1.0.0",
"newton @ git+https://github.com/newton-physics/newton.git@141baffff9",
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 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.

Suggested change
"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.)

],
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,21 +3,49 @@
#
# SPDX-License-Identifier: BSD-3-Clause

from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg
from isaaclab_physx.physics import PhysxCfg

from isaaclab.sim import SimulationCfg
from isaaclab.utils import configclass

from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import (
EventsCfg,
LocomotionVelocityRoughEnvCfg,
StartupEventsCfg,
)
from isaaclab_tasks.utils import PresetCfg
from isaaclab_tasks.utils import PresetCfg, preset

##
# Pre-defined configs
##
from isaaclab_assets.robots.anymal import ANYMAL_D_CFG # isort: skip


@configclass
class RoughPhysicsCfg(PresetCfg):
default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15)
# WAR: Rough terrain requires pyramidal cone — elliptic cone + high impratio diverges
# in float32 with many mesh contacts due to MuJoCo Warp single-precision limitations.
# Upstream (open): https://github.com/google-deepmind/mujoco_warp/issues/1000
# Also uses Newton collision pipeline (use_mujoco_contacts=False) since MuJoCo's
# built-in collision does not support mesh terrain geometry.
newton = NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=200,
nconmax=100,
cone="pyramidal",
impratio=1.0,
integrator="implicitfast",
use_mujoco_contacts=False,
ccd_iterations=100,
),
num_substeps=1,
debug_mode=False,
)
physx = default


@configclass
class AnymalDPhysxEventsCfg(EventsCfg, StartupEventsCfg):
pass
Expand All @@ -32,13 +60,17 @@ class AnymalDEventsCfg(PresetCfg):

@configclass
class AnymalDRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg())
events: AnymalDEventsCfg = AnymalDEventsCfg()

def __post_init__(self):
# post init of parent
super().__post_init__()
# switch robot to anymal-d
self.scene.robot = ANYMAL_D_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# RayCaster height scanner requires Kit (omni.physics) — disable for Newton.
self.scene.height_scanner = preset(default=self.scene.height_scanner, newton=None)
self.observations.policy.height_scan = preset(default=self.observations.policy.height_scan, newton=None)


@configclass
Expand Down