Skip to content
2 changes: 1 addition & 1 deletion source/isaaclab_newton/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.5.21"
version = "0.5.22"

# Description
title = "Newton simulation interfaces for IsaacLab core package"
Expand Down
19 changes: 19 additions & 0 deletions source/isaaclab_newton/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,25 @@
Changelog
---------

0.5.22 (2026-04-24)
~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added :class:`~isaaclab_newton.physics.NewtonShapeCfg` exposing
per-shape collision defaults (``margin``, ``gap``) via
:attr:`~isaaclab_newton.physics.NewtonCfg.default_shape_cfg`.
:meth:`~isaaclab_newton.physics.NewtonManager.create_builder` now
forwards the wrapper onto Newton's upstream
``ModelBuilder.default_shape_cfg`` via
:func:`~isaaclab.utils.checked_apply`. The previous code only set
``gap`` and left ``margin`` at Newton's upstream default of ``0.0``,
causing all non-Anymal-D robots to fail to learn rough-terrain
locomotion on triangle-mesh terrain. ``RoughPhysicsCfg`` opts in to
``margin=0.01``.


0.5.21 (2026-04-23)
~~~~~~~~~~~~~~~~~~~

Expand Down
2 changes: 2 additions & 0 deletions source/isaaclab_newton/isaaclab_newton/physics/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ __all__ = [
"NewtonCfg",
"NewtonCollisionPipelineCfg",
"NewtonManager",
"NewtonShapeCfg",
"NewtonSolverCfg",
"XPBDSolverCfg",
]
Expand All @@ -20,6 +21,7 @@ from .newton_manager_cfg import (
FeatherstoneSolverCfg,
MJWarpSolverCfg,
NewtonCfg,
NewtonShapeCfg,
NewtonSolverCfg,
XPBDSolverCfg,
)
17 changes: 15 additions & 2 deletions source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,12 @@
from isaaclab.physics import PhysicsEvent, PhysicsManager
from isaaclab.sim.utils.newton_model_utils import replace_newton_shape_colors
from isaaclab.sim.utils.stage import get_current_stage
from isaaclab.utils import checked_apply
from isaaclab.utils.string import resolve_matching_names
from isaaclab.utils.timer import Timer

from .newton_manager_cfg import NewtonCfg, NewtonShapeCfg

if TYPE_CHECKING:
from isaaclab.sim.simulation_context import SimulationContext

Expand Down Expand Up @@ -421,16 +424,26 @@ def set_builder(cls, builder: ModelBuilder) -> None:
def create_builder(cls, up_axis: str | None = None, **kwargs) -> ModelBuilder:
"""Create a :class:`ModelBuilder` configured with default settings.

Forwards :class:`NewtonShapeCfg` defaults onto Newton's upstream
``ModelBuilder.default_shape_cfg`` via :func:`~isaaclab.utils.checked_apply`.
Falls back to wrapper defaults when no Newton config is active so
rough-terrain margin/gap still apply during early construction.

Args:
up_axis: Override for the up-axis. Defaults to ``None``, which uses
the manager's ``_up_axis``.
**kwargs: Forwarded to :class:`ModelBuilder`.

Returns:
New builder with up-axis and gap defaults applied.
New builder with up-axis and per-shape defaults (gap, margin) applied.
"""
builder = ModelBuilder(up_axis=up_axis or cls._up_axis, **kwargs)
builder.default_shape_cfg.gap = 0.01
# Resolve which NewtonShapeCfg to apply: user override if active config
# is NewtonCfg, else the wrapper's own defaults so callers from non-Newton
# contexts (tests, early construction) still get the rough-terrain margin.
cfg = PhysicsManager._cfg
shape_cfg = cfg.default_shape_cfg if isinstance(cfg, NewtonCfg) else NewtonShapeCfg()
checked_apply(shape_cfg, builder.default_shape_cfg)
return builder

@classmethod
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -216,6 +216,29 @@ class FeatherstoneSolverCfg(NewtonSolverCfg):
"""Whether to fuse the Cholesky decomposition."""


@configclass
class NewtonShapeCfg:
"""Default per-shape collision properties applied to all shapes in a Newton scene.

Mirrors Newton's :attr:`ModelBuilder.default_shape_cfg`. Only fields Isaac
Lab actually overrides are declared here; unspecified fields keep Newton's
upstream default. The struct is forwarded onto Newton's upstream
``ShapeConfig`` via :func:`~isaaclab.utils.checked_apply` at builder
construction.
"""

margin: float = 0.0
"""Default per-shape collision margin [m].

A nonzero margin (e.g. ``0.01``) is required for stable contact on
triangle-mesh terrain — without it, lightweight robots fail to learn
rough-terrain locomotion on Newton. Newton's upstream default is ``0.0``.
"""

gap: float = 0.01
"""Default per-shape contact gap [m]. Newton's upstream default is ``None``."""


@configclass
class NewtonCfg(PhysicsCfg):
"""Configuration for Newton physics manager.
Expand Down Expand Up @@ -257,3 +280,11 @@ class NewtonCfg(PhysicsCfg):
.. note::
Must not be set when ``use_mujoco_contacts=True`` (raises :class:`ValueError`).
"""

default_shape_cfg: NewtonShapeCfg = NewtonShapeCfg()
"""Default per-shape collision properties applied to every shape in the scene.

Forwarded to Newton's :attr:`ModelBuilder.default_shape_cfg` at builder
construction via :func:`~isaaclab.utils.checked_apply`. See
:class:`NewtonShapeCfg` for the declared fields.
"""
2 changes: 1 addition & 1 deletion source/isaaclab_tasks/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "1.5.27"
version = "1.5.28"

# Description
title = "Isaac Lab Environments"
Expand Down
30 changes: 30 additions & 0 deletions source/isaaclab_tasks/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,36 @@
Changelog
---------

1.5.28 (2026-04-24)
~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Enabled Newton rough-terrain locomotion training on the remaining
quadrupeds (Go1, Go2, A1, Anymal-B, Anymal-C), bipeds (H1, Cassie),
Digit, and G1 on top of Octi's Anymal-D work cherry-picked from
PR #5225.
* Hoisted the per-env Anymal-D ``RoughPhysicsCfg`` (MJWarp solver +
collision pipeline) into the shared
:class:`~isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg.LocomotionVelocityRoughEnvCfg`
so every rough-terrain env inherits identical physics. The shared
preset opts in to ``default_shape_cfg=NewtonShapeCfg(margin=0.01)``,
which is the single most important Newton setting for rough terrain.
* Added Go1 Newton-only leg armature preset to improve rough-terrain
training stability on lightweight quadrupeds.

Changed
^^^^^^^

* Replaced the additive ``(-5, 5)`` kg default on
``EventsCfg.add_base_mass`` with a multiplicative ``(1/1.25, 1.25)``
log-uniform scale (``operation="scale"``,
``distribution="log_uniform"``). Scale-invariant across robot sizes
with geometric mean 1.0; removes the need for per-robot
``(-1.0, 3.0)`` additive overrides on A1/Go1/Go2.


1.5.27 (2026-04-25)
~~~~~~~~~~~~~~~~~~~

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


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.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg

##
# Pre-defined configs
##
from isaaclab_assets.robots.unitree import UNITREE_A1_CFG # isort: skip


@configclass
class A1NewtonEventsCfg(EventsCfg):
def __post_init__(self):
super().__post_init__()
self.push_robot = None
self.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
self.reset_robot_joints.params["position_range"] = (1.0, 1.0)
self.reset_base.params = {
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
"velocity_range": {
"x": (0.0, 0.0),
"y": (0.0, 0.0),
"z": (0.0, 0.0),
"roll": (0.0, 0.0),
"pitch": (0.0, 0.0),
"yaw": (0.0, 0.0),
},
}


@configclass
class A1PhysxEventsCfg(A1NewtonEventsCfg, StartupEventsCfg):
def __post_init__(self):
super().__post_init__()
self.add_base_mass.params["mass_distribution_params"] = (-1.0, 3.0)
self.add_base_mass.params["asset_cfg"].body_names = "trunk"
self.base_com = None


@configclass
class A1EventsCfg(PresetCfg):
default = A1PhysxEventsCfg()
newton = A1NewtonEventsCfg()
physx = default


@configclass
class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
events: A1EventsCfg = A1EventsCfg()

def __post_init__(self):
# post init of parent
super().__post_init__()
Expand All @@ -69,6 +27,11 @@ def __post_init__(self):
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_range = (0.01, 0.06)
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_step = 0.01

# A1 uses "trunk" as base body
self.events.add_base_mass.params["asset_cfg"].body_names = "trunk"
self.events.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
self.events.base_com.default.params["asset_cfg"].body_names = "trunk"

# reduce action scale
self.actions.joint_pos.scale = 0.25

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


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.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg

##
# Pre-defined configs
##
from isaaclab_assets import ANYMAL_B_CFG # isort: skip


@configclass
class AnymalBPhysxEventsCfg(EventsCfg, StartupEventsCfg):
pass


@configclass
class AnymalBEventsCfg(PresetCfg):
default = AnymalBPhysxEventsCfg()
newton = EventsCfg()
physx = default


@configclass
class AnymalBRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
events: AnymalBEventsCfg = AnymalBEventsCfg()

def __post_init__(self):
# post init of parent
super().__post_init__()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,37 +3,20 @@
#
# SPDX-License-Identifier: BSD-3-Clause


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, preset
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
from isaaclab_tasks.utils import preset

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


@configclass
class AnymalCPhysxEventsCfg(EventsCfg, StartupEventsCfg):
pass


@configclass
class AnymalCEventsCfg(PresetCfg):
default = AnymalCPhysxEventsCfg()
newton = EventsCfg()
physx = default


@configclass
class AnymalCRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
events: AnymalCEventsCfg = AnymalCEventsCfg()

def __post_init__(self):
# post init of parent
super().__post_init__()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,37 +3,19 @@
#
# SPDX-License-Identifier: BSD-3-Clause


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.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg

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


@configclass
class AnymalDPhysxEventsCfg(EventsCfg, StartupEventsCfg):
pass


@configclass
class AnymalDEventsCfg(PresetCfg):
default = AnymalDPhysxEventsCfg()
newton = EventsCfg()
physx = default


@configclass
class AnymalDRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
events: AnymalDEventsCfg = AnymalDEventsCfg()

def __post_init__(self):
# post init of parent
super().__post_init__()
Expand Down
Loading
Loading