Skip to content

Commit e32f9d8

Browse files
committed
Enable rough terrain on all locomotion envs with shared NewtonShapeCfg
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
1 parent c2f7eeb commit e32f9d8

19 files changed

Lines changed: 218 additions & 360 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.21"
4+
version = "0.5.22"
55

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

source/isaaclab_newton/docs/CHANGELOG.rst

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,25 @@
11
Changelog
22
---------
33

4+
0.5.22 (2026-04-24)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Added
8+
^^^^^
9+
10+
* Added :class:`~isaaclab_newton.physics.NewtonShapeCfg` exposing
11+
per-shape collision defaults (``margin``, ``gap``) via
12+
:attr:`~isaaclab_newton.physics.NewtonCfg.default_shape_cfg`.
13+
:meth:`~isaaclab_newton.physics.NewtonManager.create_builder` now
14+
forwards the wrapper onto Newton's upstream
15+
``ModelBuilder.default_shape_cfg`` via
16+
:func:`~isaaclab.utils.checked_apply`. The previous code only set
17+
``gap`` and left ``margin`` at Newton's upstream default of ``0.0``,
18+
causing all non-Anymal-D robots to fail to learn rough-terrain
19+
locomotion on triangle-mesh terrain. ``RoughPhysicsCfg`` opts in to
20+
``margin=0.01``.
21+
22+
423
0.5.21 (2026-04-23)
524
~~~~~~~~~~~~~~~~~~~
625

source/isaaclab_newton/isaaclab_newton/physics/__init__.pyi

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@ __all__ = [
1010
"NewtonCfg",
1111
"NewtonCollisionPipelineCfg",
1212
"NewtonManager",
13+
"NewtonShapeCfg",
1314
"NewtonSolverCfg",
1415
"XPBDSolverCfg",
1516
]
@@ -20,6 +21,7 @@ from .newton_manager_cfg import (
2021
FeatherstoneSolverCfg,
2122
MJWarpSolverCfg,
2223
NewtonCfg,
24+
NewtonShapeCfg,
2325
NewtonSolverCfg,
2426
XPBDSolverCfg,
2527
)

source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py

Lines changed: 15 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,12 @@
3636
from isaaclab.physics import PhysicsEvent, PhysicsManager
3737
from isaaclab.sim.utils.newton_model_utils import replace_newton_shape_colors
3838
from isaaclab.sim.utils.stage import get_current_stage
39+
from isaaclab.utils import checked_apply
3940
from isaaclab.utils.string import resolve_matching_names
4041
from isaaclab.utils.timer import Timer
4142

43+
from .newton_manager_cfg import NewtonCfg, NewtonShapeCfg
44+
4245
if TYPE_CHECKING:
4346
from isaaclab.sim.simulation_context import SimulationContext
4447

@@ -421,16 +424,26 @@ def set_builder(cls, builder: ModelBuilder) -> None:
421424
def create_builder(cls, up_axis: str | None = None, **kwargs) -> ModelBuilder:
422425
"""Create a :class:`ModelBuilder` configured with default settings.
423426
427+
Forwards :class:`NewtonShapeCfg` defaults onto Newton's upstream
428+
``ModelBuilder.default_shape_cfg`` via :func:`~isaaclab.utils.checked_apply`.
429+
Falls back to wrapper defaults when no Newton config is active so
430+
rough-terrain margin/gap still apply during early construction.
431+
424432
Args:
425433
up_axis: Override for the up-axis. Defaults to ``None``, which uses
426434
the manager's ``_up_axis``.
427435
**kwargs: Forwarded to :class:`ModelBuilder`.
428436
429437
Returns:
430-
New builder with up-axis and gap defaults applied.
438+
New builder with up-axis and per-shape defaults (gap, margin) applied.
431439
"""
432440
builder = ModelBuilder(up_axis=up_axis or cls._up_axis, **kwargs)
433-
builder.default_shape_cfg.gap = 0.01
441+
# Resolve which NewtonShapeCfg to apply: user override if active config
442+
# is NewtonCfg, else the wrapper's own defaults so callers from non-Newton
443+
# contexts (tests, early construction) still get the rough-terrain margin.
444+
cfg = PhysicsManager._cfg
445+
shape_cfg = cfg.default_shape_cfg if isinstance(cfg, NewtonCfg) else NewtonShapeCfg()
446+
checked_apply(shape_cfg, builder.default_shape_cfg)
434447
return builder
435448

436449
@classmethod

source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -216,6 +216,29 @@ class FeatherstoneSolverCfg(NewtonSolverCfg):
216216
"""Whether to fuse the Cholesky decomposition."""
217217

218218

219+
@configclass
220+
class NewtonShapeCfg:
221+
"""Default per-shape collision properties applied to all shapes in a Newton scene.
222+
223+
Mirrors Newton's :attr:`ModelBuilder.default_shape_cfg`. Only fields Isaac
224+
Lab actually overrides are declared here; unspecified fields keep Newton's
225+
upstream default. The struct is forwarded onto Newton's upstream
226+
``ShapeConfig`` via :func:`~isaaclab.utils.checked_apply` at builder
227+
construction.
228+
"""
229+
230+
margin: float = 0.0
231+
"""Default per-shape collision margin [m].
232+
233+
A nonzero margin (e.g. ``0.01``) is required for stable contact on
234+
triangle-mesh terrain — without it, lightweight robots fail to learn
235+
rough-terrain locomotion on Newton. Newton's upstream default is ``0.0``.
236+
"""
237+
238+
gap: float = 0.01
239+
"""Default per-shape contact gap [m]. Newton's upstream default is ``None``."""
240+
241+
219242
@configclass
220243
class NewtonCfg(PhysicsCfg):
221244
"""Configuration for Newton physics manager.
@@ -257,3 +280,11 @@ class NewtonCfg(PhysicsCfg):
257280
.. note::
258281
Must not be set when ``use_mujoco_contacts=True`` (raises :class:`ValueError`).
259282
"""
283+
284+
default_shape_cfg: NewtonShapeCfg = NewtonShapeCfg()
285+
"""Default per-shape collision properties applied to every shape in the scene.
286+
287+
Forwarded to Newton's :attr:`ModelBuilder.default_shape_cfg` at builder
288+
construction via :func:`~isaaclab.utils.checked_apply`. See
289+
:class:`NewtonShapeCfg` for the declared fields.
290+
"""

source/isaaclab_tasks/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 = "1.5.24"
4+
version = "1.5.25"
55

66
# Description
77
title = "Isaac Lab Environments"

source/isaaclab_tasks/docs/CHANGELOG.rst

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,36 @@
11
Changelog
22
---------
33

4+
1.5.25 (2026-04-24)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Added
8+
^^^^^
9+
10+
* Enabled Newton rough-terrain locomotion training on the remaining
11+
quadrupeds (Go1, Go2, A1, Anymal-B, Anymal-C), bipeds (H1, Cassie),
12+
Digit, and G1 on top of Octi's Anymal-D work cherry-picked from
13+
PR #5225.
14+
* Hoisted the per-env Anymal-D ``RoughPhysicsCfg`` (MJWarp solver +
15+
collision pipeline) into the shared
16+
:class:`~isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg.LocomotionVelocityRoughEnvCfg`
17+
so every rough-terrain env inherits identical physics. The shared
18+
preset opts in to ``default_shape_cfg=NewtonShapeCfg(margin=0.01)``,
19+
which is the single most important Newton setting for rough terrain.
20+
* Added Go1 Newton-only leg armature preset to improve rough-terrain
21+
training stability on lightweight quadrupeds.
22+
23+
Changed
24+
^^^^^^^
25+
26+
* Replaced the additive ``(-5, 5)`` kg default on
27+
``EventsCfg.add_base_mass`` with a multiplicative ``(1/1.25, 1.25)``
28+
log-uniform scale (``operation="scale"``,
29+
``distribution="log_uniform"``). Scale-invariant across robot sizes
30+
with geometric mean 1.0; removes the need for per-robot
31+
``(-1.0, 3.0)`` additive overrides on A1/Go1/Go2.
32+
33+
434
1.5.24 (2026-04-22)
535
~~~~~~~~~~~~~~~~~~~
636

source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/a1/rough_env_cfg.py

Lines changed: 7 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -3,61 +3,19 @@
33
#
44
# SPDX-License-Identifier: BSD-3-Clause
55

6+
67
from isaaclab.utils import configclass
78

8-
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import (
9-
EventsCfg,
10-
LocomotionVelocityRoughEnvCfg,
11-
StartupEventsCfg,
12-
)
13-
from isaaclab_tasks.utils import PresetCfg
9+
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
1410

1511
##
1612
# Pre-defined configs
1713
##
1814
from isaaclab_assets.robots.unitree import UNITREE_A1_CFG # isort: skip
1915

2016

21-
@configclass
22-
class A1NewtonEventsCfg(EventsCfg):
23-
def __post_init__(self):
24-
super().__post_init__()
25-
self.push_robot = None
26-
self.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
27-
self.reset_robot_joints.params["position_range"] = (1.0, 1.0)
28-
self.reset_base.params = {
29-
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
30-
"velocity_range": {
31-
"x": (0.0, 0.0),
32-
"y": (0.0, 0.0),
33-
"z": (0.0, 0.0),
34-
"roll": (0.0, 0.0),
35-
"pitch": (0.0, 0.0),
36-
"yaw": (0.0, 0.0),
37-
},
38-
}
39-
40-
41-
@configclass
42-
class A1PhysxEventsCfg(A1NewtonEventsCfg, StartupEventsCfg):
43-
def __post_init__(self):
44-
super().__post_init__()
45-
self.add_base_mass.params["mass_distribution_params"] = (-1.0, 3.0)
46-
self.add_base_mass.params["asset_cfg"].body_names = "trunk"
47-
self.base_com = None
48-
49-
50-
@configclass
51-
class A1EventsCfg(PresetCfg):
52-
default = A1PhysxEventsCfg()
53-
newton = A1NewtonEventsCfg()
54-
physx = default
55-
56-
5717
@configclass
5818
class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
59-
events: A1EventsCfg = A1EventsCfg()
60-
6119
def __post_init__(self):
6220
# post init of parent
6321
super().__post_init__()
@@ -69,6 +27,11 @@ def __post_init__(self):
6927
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_range = (0.01, 0.06)
7028
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_step = 0.01
7129

30+
# A1 uses "trunk" as base body
31+
self.events.add_base_mass.params["asset_cfg"].body_names = "trunk"
32+
self.events.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
33+
self.events.base_com.default.params["asset_cfg"].body_names = "trunk"
34+
7235
# reduce action scale
7336
self.actions.joint_pos.scale = 0.25
7437

source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py

Lines changed: 2 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -3,37 +3,19 @@
33
#
44
# SPDX-License-Identifier: BSD-3-Clause
55

6+
67
from isaaclab.utils import configclass
78

8-
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import (
9-
EventsCfg,
10-
LocomotionVelocityRoughEnvCfg,
11-
StartupEventsCfg,
12-
)
13-
from isaaclab_tasks.utils import PresetCfg
9+
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
1410

1511
##
1612
# Pre-defined configs
1713
##
1814
from isaaclab_assets import ANYMAL_B_CFG # isort: skip
1915

2016

21-
@configclass
22-
class AnymalBPhysxEventsCfg(EventsCfg, StartupEventsCfg):
23-
pass
24-
25-
26-
@configclass
27-
class AnymalBEventsCfg(PresetCfg):
28-
default = AnymalBPhysxEventsCfg()
29-
newton = EventsCfg()
30-
physx = default
31-
32-
3317
@configclass
3418
class AnymalBRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
35-
events: AnymalBEventsCfg = AnymalBEventsCfg()
36-
3719
def __post_init__(self):
3820
# post init of parent
3921
super().__post_init__()

source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py

Lines changed: 3 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -3,37 +3,20 @@
33
#
44
# SPDX-License-Identifier: BSD-3-Clause
55

6+
67
from isaaclab.utils import configclass
78

8-
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import (
9-
EventsCfg,
10-
LocomotionVelocityRoughEnvCfg,
11-
StartupEventsCfg,
12-
)
13-
from isaaclab_tasks.utils import PresetCfg, preset
9+
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
10+
from isaaclab_tasks.utils import preset
1411

1512
##
1613
# Pre-defined configs
1714
##
1815
from isaaclab_assets.robots.anymal import ANYMAL_C_CFG # isort: skip
1916

2017

21-
@configclass
22-
class AnymalCPhysxEventsCfg(EventsCfg, StartupEventsCfg):
23-
pass
24-
25-
26-
@configclass
27-
class AnymalCEventsCfg(PresetCfg):
28-
default = AnymalCPhysxEventsCfg()
29-
newton = EventsCfg()
30-
physx = default
31-
32-
3318
@configclass
3419
class AnymalCRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
35-
events: AnymalCEventsCfg = AnymalCEventsCfg()
36-
3720
def __post_init__(self):
3821
# post init of parent
3922
super().__post_init__()

0 commit comments

Comments
 (0)