Skip to content

Commit 78d607b

Browse files
committed
Squashed commit of the following:
commit 7bab8a0 Author: Octi Zhang <zhengyuz@nvidia.com> Date: Thu Apr 9 18:11:47 2026 -0700 line break commit c9c1a29 Author: Octi Zhang <zhengyuz@nvidia.com> Date: Thu Apr 9 18:09:32 2026 -0700 Add collision pipeline cfg, bump to 0.5.11 Add NewtonCollisionPipelineCfg and HydroelasticSDFCfg to expose Newton's collision pipeline parameters (broad phase, contact limits, hydroelastic mode) through NewtonCfg.collision_cfg. Add MJWarpSolverCfg.tolerance for solver convergence control. Fix validation order so collision_cfg is stored before the use_mujoco_contacts consistency check runs. Reset _collision_cfg in clear() to avoid stale state across reset cycles. Fall back to a default CollisionPipeline when collision_cfg is None. commit 43ae9f3 Author: Octi Zhang <zhengyuz@nvidia.com> Date: Thu Apr 9 18:06:21 2026 -0700 expose newton collision cfg
1 parent 9473bee commit 78d607b

6 files changed

Lines changed: 254 additions & 14 deletions

File tree

source/isaaclab_newton/config/extension.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
[package]
22

33
# Note: Semantic Versioning is used: https://semver.org/
4-
version = "0.5.10"
4+
version = "0.5.11"
55

66
# Description
77
title = "Newton simulation interfaces for IsaacLab core package"

source/isaaclab_newton/docs/CHANGELOG.rst

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
Changelog
22
---------
33

4+
45
0.5.13 (2026-04-09)
56
~~~~~~~~~~~~~~~~~~~
67

@@ -11,8 +12,17 @@ Added
1112
backend implementation for xform prim views.
1213

1314

14-
0.5.11 (2026-04-09)
15+
0.5.12 (2026-04-09)
16+
~~~~~~~~~~~~~~~~~~~
17+
Added
18+
^^^^^
1519

20+
* Added :class:`~isaaclab_newton.physics.NewtonCollisionPipelineCfg` to expose Newton collision pipeline parameters via
21+
:attr:`~isaaclab_newton.physics.NewtonCfg.collision_cfg`.
22+
23+
24+
0.5.11 (2026-04-09)
25+
~~~~~~~~~~~~~~~~~~~
1626
Added
1727
^^^^^
1828

source/isaaclab_newton/isaaclab_newton/physics/__init__.pyi

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,21 @@
55

66
__all__ = [
77
"FeatherstoneSolverCfg",
8+
"HydroelasticSDFCfg",
89
"MJWarpSolverCfg",
910
"NewtonCfg",
11+
"NewtonCollisionPipelineCfg",
1012
"NewtonManager",
1113
"NewtonSolverCfg",
1214
"XPBDSolverCfg",
1315
]
1416

17+
from .newton_collision_cfg import HydroelasticSDFCfg, NewtonCollisionPipelineCfg
1518
from .newton_manager import NewtonManager
16-
from .newton_manager_cfg import FeatherstoneSolverCfg, MJWarpSolverCfg, NewtonCfg, NewtonSolverCfg, XPBDSolverCfg
19+
from .newton_manager_cfg import (
20+
FeatherstoneSolverCfg,
21+
MJWarpSolverCfg,
22+
NewtonCfg,
23+
NewtonSolverCfg,
24+
XPBDSolverCfg,
25+
)
Lines changed: 168 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,168 @@
1+
# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2+
# All rights reserved.
3+
#
4+
# SPDX-License-Identifier: BSD-3-Clause
5+
6+
"""Configuration for Newton collision pipeline."""
7+
8+
from __future__ import annotations
9+
10+
from typing import Literal
11+
12+
from isaaclab.utils import configclass
13+
14+
15+
@configclass
16+
class HydroelasticSDFCfg:
17+
"""Configuration for SDF-based hydroelastic collision handling.
18+
19+
Hydroelastic contacts generate distributed contact areas instead of point contacts,
20+
providing more realistic force distribution for manipulation and compliant surfaces.
21+
22+
For more details, see the `Newton Collisions Guide`_.
23+
24+
.. _Newton Collisions Guide: https://newton-physics.github.io/newton/latest/concepts/collisions.html#hydroelastic-contacts
25+
"""
26+
27+
reduce_contacts: bool = True
28+
"""Whether to reduce contacts to a smaller representative set per shape pair.
29+
30+
When False, all generated contacts are passed through without reduction.
31+
32+
Defaults to ``True`` (same as Newton's default).
33+
"""
34+
35+
buffer_fraction: float = 1.0
36+
"""Fraction of worst-case hydroelastic buffer allocations. Range: (0, 1].
37+
38+
Lower values reduce memory usage but may cause overflows in dense scenes.
39+
Overflows are bounds-safe and emit warnings; increase this value when warnings appear.
40+
41+
Defaults to ``1.0`` (same as Newton's default).
42+
"""
43+
44+
normal_matching: bool = True
45+
"""Whether to rotate reduced contact normals to align with aggregate force direction.
46+
47+
Only active when ``reduce_contacts`` is True.
48+
49+
Defaults to ``True`` (same as Newton's default).
50+
"""
51+
52+
anchor_contact: bool = False
53+
"""Whether to add an anchor contact at the center of pressure for each normal bin.
54+
55+
The anchor contact helps preserve moment balance. Only active when ``reduce_contacts`` is True.
56+
57+
Defaults to ``False`` (same as Newton's default).
58+
"""
59+
60+
margin_contact_area: float = 0.01
61+
"""Contact area [m^2] used for non-penetrating contacts at the margin.
62+
63+
Defaults to ``0.01`` (same as Newton's default).
64+
"""
65+
66+
output_contact_surface: bool = False
67+
"""Whether to output hydroelastic contact surface vertices for visualization.
68+
69+
Defaults to ``False`` (same as Newton's default).
70+
"""
71+
72+
73+
@configclass
74+
class NewtonCollisionPipelineCfg:
75+
"""Configuration for Newton collision pipeline.
76+
77+
Full-featured collision pipeline with GJK/MPR narrow phase and pluggable broad phase.
78+
When this config is set on :attr:`NewtonCfg.collision_cfg`:
79+
80+
- **MJWarpSolverCfg**: Newton's collision pipeline replaces MuJoCo's internal contact solver.
81+
- **Other solvers** (XPBD, Featherstone, etc.): Configures the collision pipeline parameters
82+
(these solvers always use Newton's collision pipeline).
83+
84+
Key features:
85+
86+
- GJK/MPR algorithms for convex-convex collision detection
87+
- Multiple broad phase options: NXN (all-pairs), SAP (sweep-and-prune), EXPLICIT (precomputed pairs)
88+
- Mesh-mesh collision via SDF with contact reduction
89+
- Optional hydroelastic contact model for compliant surfaces
90+
91+
For more details, see the `Newton Collisions Guide`_ and `CollisionPipeline API`_.
92+
93+
.. _Newton Collisions Guide: https://newton-physics.github.io/newton/latest/concepts/collisions.html
94+
.. _CollisionPipeline API: https://newton-physics.github.io/newton/api/_generated/newton.CollisionPipeline.html
95+
"""
96+
97+
broad_phase: Literal["explicit", "nxn", "sap"] = "explicit"
98+
"""Broad phase algorithm for collision detection.
99+
100+
Options:
101+
102+
- ``"explicit"``: Use precomputed shape pairs from ``model.shape_contact_pairs``.
103+
- ``"nxn"``: All-pairs brute force. Simple but O(n^2) complexity.
104+
- ``"sap"``: Sweep-and-prune. Good for scenes with many dynamic objects.
105+
106+
Defaults to ``"explicit"`` (same as Newton's default when ``broad_phase=None``).
107+
"""
108+
109+
reduce_contacts: bool = True
110+
"""Whether to reduce contacts for mesh-mesh collisions.
111+
112+
When True, uses shared memory contact reduction to select representative contacts.
113+
Improves performance and stability for meshes with many vertices.
114+
115+
Defaults to ``True`` (same as Newton's default).
116+
"""
117+
118+
rigid_contact_max: int | None = None
119+
"""Maximum number of rigid contacts to allocate.
120+
121+
Resolution order:
122+
123+
1. If provided, use this value.
124+
2. Else if ``model.rigid_contact_max > 0``, use the model value.
125+
3. Else estimate automatically from model shape and pair metadata.
126+
127+
Defaults to ``None`` (auto-estimate, same as Newton's default).
128+
"""
129+
130+
max_triangle_pairs: int = 1_000_000
131+
"""Maximum number of triangle pairs allocated by narrow phase for mesh and heightfield collisions.
132+
133+
Increase this when scenes with large/complex meshes or heightfields report
134+
triangle-pair overflow warnings.
135+
136+
Defaults to ``1_000_000`` (same as Newton's default).
137+
"""
138+
139+
soft_contact_max: int | None = None
140+
"""Maximum number of soft contacts to allocate.
141+
142+
If None, computed as ``shape_count * particle_count``.
143+
144+
Defaults to ``None`` (auto-compute, same as Newton's default).
145+
"""
146+
147+
soft_contact_margin: float = 0.01
148+
"""Margin [m] for soft contact generation.
149+
150+
Defaults to ``0.01`` (same as Newton's default).
151+
"""
152+
153+
requires_grad: bool | None = None
154+
"""Whether to enable gradient computation for collision.
155+
156+
If ``None``, uses ``model.requires_grad``.
157+
158+
Defaults to ``None`` (same as Newton's default).
159+
"""
160+
161+
sdf_hydroelastic_config: HydroelasticSDFCfg | None = None
162+
"""Configuration for SDF-based hydroelastic collision handling.
163+
164+
If ``None``, hydroelastic contacts are disabled.
165+
If set, enables hydroelastic contacts with the specified parameters.
166+
167+
Defaults to ``None`` (hydroelastic disabled, same as Newton's default).
168+
"""

source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py

Lines changed: 23 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
_cudart = None
2929
from newton import Axis, CollisionPipeline, Contacts, Control, Model, ModelBuilder, State, eval_fk
3030
from newton._src.usd.schemas import SchemaResolverNewton, SchemaResolverPhysx
31+
from newton.geometry import HydroelasticSDF
3132
from newton.sensors import SensorContact as NewtonContactSensor
3233
from newton.solvers import SolverBase, SolverFeatherstone, SolverMuJoCo, SolverNotifyFlags, SolverXPBD
3334

@@ -38,6 +39,8 @@
3839
if TYPE_CHECKING:
3940
from isaaclab.sim.simulation_context import SimulationContext
4041

42+
from .newton_collision_cfg import NewtonCollisionPipelineCfg
43+
4144
logger = logging.getLogger(__name__)
4245

4346

@@ -91,6 +94,7 @@ class NewtonManager(PhysicsManager):
9194
_contacts: Contacts | None = None
9295
_needs_collision_pipeline: bool = False
9396
_collision_pipeline = None
97+
_collision_cfg: NewtonCollisionPipelineCfg | None = None
9498
_newton_contact_sensors: dict = {} # Maps sensor_key to NewtonContactSensor
9599
_report_contacts: bool = False
96100
_fk_dirty: bool = False
@@ -365,6 +369,7 @@ def clear(cls):
365369
cls._contacts = None
366370
cls._needs_collision_pipeline = False
367371
cls._collision_pipeline = None
372+
cls._collision_cfg = None
368373
cls._newton_contact_sensors = {}
369374
cls._report_contacts = False
370375
cls._fk_dirty = False
@@ -532,7 +537,15 @@ def _initialize_contacts(cls) -> None:
532537
if cls._needs_collision_pipeline:
533538
# Newton collision pipeline: create pipeline and generate contacts
534539
if cls._collision_pipeline is None:
535-
cls._collision_pipeline = CollisionPipeline(cls._model, broad_phase="explicit")
540+
if cls._collision_cfg is not None:
541+
cfg_dict = cls._collision_cfg.to_dict()
542+
hydro_cfg = cfg_dict.pop("sdf_hydroelastic_config", None)
543+
if hydro_cfg:
544+
cfg_dict["sdf_hydroelastic_config"] = HydroelasticSDF.Config(**hydro_cfg)
545+
cls._collision_pipeline = CollisionPipeline(cls._model, **cfg_dict)
546+
else:
547+
cls._collision_pipeline = CollisionPipeline(cls._model, broad_phase="explicit")
548+
536549
if cls._contacts is None:
537550
cls._contacts = cls._collision_pipeline.contacts()
538551

@@ -592,19 +605,20 @@ def initialize_solver(cls) -> None:
592605
else:
593606
raise ValueError(f"Invalid solver type: {cls._solver_type}")
594607

608+
# Store collision pipeline config
609+
cls._collision_cfg = cfg.collision_cfg # type: ignore[union-attr]
610+
595611
# Determine if we need external collision detection
596612
# - SolverMuJoCo with use_mujoco_contacts=True: uses internal MuJoCo collision detection
597613
# - SolverMuJoCo with use_mujoco_contacts=False: needs Newton's unified collision pipeline
598614
# - Other solvers (XPBD, Featherstone): always need Newton's unified collision pipeline
599615
if isinstance(cls._solver, SolverMuJoCo):
600-
# Handle both dict and object configs
601-
if hasattr(solver_cfg, "use_mujoco_contacts"):
602-
use_mujoco_contacts = solver_cfg.use_mujoco_contacts
603-
elif isinstance(solver_cfg, dict):
604-
use_mujoco_contacts = solver_cfg.get("use_mujoco_contacts", False)
605-
else:
606-
use_mujoco_contacts = getattr(solver_cfg, "use_mujoco_contacts", False)
607-
cls._needs_collision_pipeline = not use_mujoco_contacts
616+
cls._needs_collision_pipeline = not solver_cfg.use_mujoco_contacts
617+
if solver_cfg.use_mujoco_contacts and cls._collision_cfg is not None:
618+
raise ValueError(
619+
"NewtonManager: collision_cfg cannot be set when use_mujoco_contacts=True."
620+
" Either set use_mujoco_contacts=False or remove collision_cfg."
621+
)
608622
else:
609623
cls._needs_collision_pipeline = True
610624

source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py

Lines changed: 41 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,10 @@
1212
from isaaclab.physics import PhysicsCfg
1313
from isaaclab.utils import configclass
1414

15+
from .newton_collision_cfg import NewtonCollisionPipelineCfg
16+
1517
if TYPE_CHECKING:
16-
from .newton_manager import NewtonManager
18+
from isaaclab_newton.physics import NewtonManager
1719

1820

1921
@configclass
@@ -104,7 +106,27 @@ class MJWarpSolverCfg(NewtonSolverCfg):
104106
"""Whether to use parallel line search."""
105107

106108
use_mujoco_contacts: bool = True
107-
"""Whether to use MuJoCo's contact solver."""
109+
"""Whether to use MuJoCo's internal contact solver.
110+
111+
If ``True`` (default), MuJoCo handles collision detection and contact resolution internally.
112+
If ``False``, Newton's :class:`CollisionPipeline` is used instead. A default pipeline
113+
(``broad_phase="explicit"``) is created automatically when :attr:`NewtonCfg.collision_cfg`
114+
is ``None``. Set :attr:`NewtonCfg.collision_cfg` to a :class:`NewtonCollisionPipelineCfg`
115+
to customize pipeline parameters (broad phase, contact limits, hydroelastic, etc.).
116+
117+
.. note::
118+
Setting ``collision_cfg`` while ``use_mujoco_contacts=True`` raises
119+
:class:`ValueError` because the two collision modes are mutually exclusive.
120+
"""
121+
122+
tolerance: float = 1e-6
123+
"""Solver convergence tolerance for the constraint residual.
124+
125+
The solver iterates until the residual drops below this threshold or
126+
``iterations`` is reached. Lower values give more precise constraint
127+
satisfaction at the cost of more iterations. MuJoCo default is ``1e-8``;
128+
Newton default is ``1e-6``.
129+
"""
108130

109131

110132
@configclass
@@ -218,3 +240,20 @@ class NewtonCfg(PhysicsCfg):
218240

219241
solver_cfg: NewtonSolverCfg = MJWarpSolverCfg()
220242
"""Solver configuration. Default is MJWarpSolverCfg()."""
243+
244+
collision_cfg: NewtonCollisionPipelineCfg | None = None
245+
"""Newton collision pipeline configuration.
246+
247+
Controls how Newton's :class:`CollisionPipeline` is configured when it is active.
248+
The pipeline is active when:
249+
250+
- :class:`MJWarpSolverCfg` with ``use_mujoco_contacts=False``, or
251+
- any non-MuJoCo solver (:class:`XPBDSolverCfg`, :class:`FeatherstoneSolverCfg`).
252+
253+
If ``None`` (default), a pipeline with ``broad_phase="explicit"`` is created
254+
automatically. Set this to a :class:`NewtonCollisionPipelineCfg` to customize
255+
parameters such as broad phase algorithm, contact limits, or hydroelastic mode.
256+
257+
.. note::
258+
Must not be set when ``use_mujoco_contacts=True`` (raises :class:`ValueError`).
259+
"""

0 commit comments

Comments
 (0)