From f7202c0c662d950ff8a0f6d96e8794be9fa8f392 Mon Sep 17 00:00:00 2001 From: hujc Date: Fri, 24 Apr 2026 03:53:52 +0000 Subject: [PATCH 1/5] Add checked_apply helper for forwarding configclass fields onto upstream dataclasses MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit When an Isaac Lab configclass mirrors an upstream library's dataclass (for example NewtonShapeCfg → Newton's ShapeConfig), bare setattr loops are fragile: if upstream renames or removes a field, every write becomes a silent no-op (the failure mode PR #5289 fixed for ShapeConfig.contact_margin → margin). Add isaaclab.utils.checked_apply(src, target): - Iterates fields(src) — single source of truth for declared fields - Raises AttributeError if target lacks a declared field — failure surfaces at startup, not at runtime - One-line apply at the call site, no per-field setattr noise --- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 13 ++++ source/isaaclab/isaaclab/utils/__init__.pyi | 3 +- source/isaaclab/isaaclab/utils/configclass.py | 35 +++++++++++ .../isaaclab/test/utils/test_configclass.py | 63 +++++++++++++++++++ 5 files changed, 114 insertions(+), 2 deletions(-) diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 3086a2b93c88..fad2b53b6c5e 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "4.6.12" +version = "4.6.13" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index ce6db83354dd..14076a4048d9 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,19 @@ Changelog --------- +4.6.13 (2026-04-24) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added :func:`~isaaclab.utils.checked_apply` for forwarding declared + fields from an Isaac Lab configclass onto an external dataclass + (typically an upstream library config object). Raises + :class:`AttributeError` if the target is missing a declared field, so + upstream renames surface at startup instead of as silent no-ops. + + 4.6.12 (2026-04-23) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/utils/__init__.pyi b/source/isaaclab/isaaclab/utils/__init__.pyi index 1ca7ef7866c6..e9f5e201ca21 100644 --- a/source/isaaclab/isaaclab/utils/__init__.pyi +++ b/source/isaaclab/isaaclab/utils/__init__.pyi @@ -56,6 +56,7 @@ __all__ = [ "compare_versions", "configclass", "resolve_cfg_presets", + "checked_apply", ] from .timer import Timer @@ -106,4 +107,4 @@ from .string import ( ) from .types import ArticulationActions from .version import has_kit, get_isaac_sim_version, compare_versions -from .configclass import configclass, resolve_cfg_presets +from .configclass import checked_apply, configclass, resolve_cfg_presets diff --git a/source/isaaclab/isaaclab/utils/configclass.py b/source/isaaclab/isaaclab/utils/configclass.py index 7b0ed789bceb..59605f2797cc 100644 --- a/source/isaaclab/isaaclab/utils/configclass.py +++ b/source/isaaclab/isaaclab/utils/configclass.py @@ -5,6 +5,7 @@ """Sub-module that provides a wrapper around the Python 3.7 onwards ``dataclasses`` module.""" +import dataclasses import inspect import re import types @@ -633,3 +634,37 @@ def resolve_cfg_presets(cfg: object) -> object: else: resolve_cfg_presets(value) return cfg + + +def checked_apply(src: Any, target: Any) -> None: + """Forward every declared field on ``src`` (a dataclass) onto ``target``. + + Used by Isaac Lab configclasses that mirror an upstream/external dataclass + (for example, Newton's ``ShapeConfig``): declare the overridable fields + once on the wrapper, then forward them to the upstream object via this + helper instead of writing ``setattr`` lines per field. + + Raises :class:`AttributeError` if ``target`` is missing a field declared + on ``src``. The two structures must match — the check guards against + silent no-ops when the upstream API drifts (the bug class PR #5289 fixed + for Newton ``ShapeConfig.contact_margin`` → ``margin``). + + Args: + src: Dataclass instance whose declared fields will be forwarded. + Field names live here; this is the single source of truth. + target: Object to receive the field values. Must already expose + an attribute for every declared field on ``src``. + + Raises: + AttributeError: If ``target`` does not already have an attribute + matching one of ``src``'s declared field names. + """ + if not hasattr(src, "__dataclass_fields__"): + raise TypeError(f"checked_apply: src must be a dataclass, got {type(src).__name__}") + for f in dataclasses.fields(src): + if not hasattr(target, f.name): + target_path = f"{type(target).__module__}.{type(target).__name__}" + raise AttributeError( + f"{target_path} has no attribute `{f.name}`. {type(src).__name__} is out of sync with target." + ) + setattr(target, f.name, getattr(src, f.name)) diff --git a/source/isaaclab/test/utils/test_configclass.py b/source/isaaclab/test/utils/test_configclass.py index 716c834cc3e1..60f77367e066 100644 --- a/source/isaaclab/test/utils/test_configclass.py +++ b/source/isaaclab/test/utils/test_configclass.py @@ -1145,3 +1145,66 @@ class ChildCfg(ParentCfg): assert _field_module_dir(child, "class_type") == "some_package.sub_package" # extra should resolve to the child's module dir assert _field_module_dir(child, "extra") == "test_some_feature" + + +# ============================================================================= +# Tests: checked_apply +# ============================================================================= + + +def test_checked_apply_forwards_all_fields(): + """checked_apply forwards every declared field on src onto target.""" + from dataclasses import dataclass as plain_dataclass + + from isaaclab.utils import checked_apply + + @configclass + class WrapperCfg: + gap: float = 0.01 + margin: float = 0.0 + + @plain_dataclass + class UpstreamLike: + gap: float = 99.0 + margin: float = 99.0 + unrelated: str = "keep me" + + src = WrapperCfg(margin=0.005) + target = UpstreamLike() + checked_apply(src, target) + + assert target.gap == 0.01 + assert target.margin == 0.005 + # fields not declared on src are not touched + assert target.unrelated == "keep me" + + +def test_checked_apply_raises_on_missing_target_field(): + """checked_apply fails loudly when target lacks a declared field.""" + from dataclasses import dataclass as plain_dataclass + + from isaaclab.utils import checked_apply + + @configclass + class WrapperCfg: + margin: float = 0.01 + renamed_in_upstream: float = 0.0 + + @plain_dataclass + class UpstreamMissingField: + margin: float = 0.0 + # 'renamed_in_upstream' was renamed/removed upstream + + with pytest.raises(AttributeError, match="renamed_in_upstream"): + checked_apply(WrapperCfg(), UpstreamMissingField()) + + +def test_checked_apply_rejects_non_dataclass_src(): + """checked_apply requires src to be a dataclass.""" + from isaaclab.utils import checked_apply + + class NotADataclass: + margin = 0.01 + + with pytest.raises(TypeError, match="must be a dataclass"): + checked_apply(NotADataclass(), object()) From aa6caed744634aa24e206de87753fa4ee3429dd1 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sat, 11 Apr 2026 01:51:00 -0700 Subject: [PATCH 2/5] Cherry-pick: Anymal-D rough terrain (subset) from #5225 Originally Octi's commit on PR #5225. Cherry-picked here so the rough terrain stack does not depend on his still-open WIP PR while he is away. Included from #5225: - source/isaaclab_tasks/.../config/anymal_d/rough_env_cfg.py: Anymal-D SimulationCfg-based RoughPhysicsCfg (MJWarp solver + collision pipeline). The shared parent will hoist this in the next commit. - source/isaaclab_tasks/.../velocity/velocity_env_cfg.py: Hoist physics_material, add_base_mass, base_com startup events into the shared EventsCfg. base_com guarded with preset(newton=None) per ablation A4 (without the gate, 99.99% of episodes terminate from body_lin_vel runaway on Newton). Upstream Newton fix https://github.com/newton-physics/newton/pull/2332 will let us drop the gate once it ships in a release. Dropped from #5225 (no longer needed): - collider_offsets startup event in velocity_env_cfg.py: per ablation A3 (clobbers shape margin via gap = max(0, contact_offset - margin) = 0, costing -3.71 reward on Anymal-D) and greptile P1 (PhysX-only root_view methods, raises AttributeError on Newton without a guard). - body_lin_vel_out_of_limit / body_ang_vel_out_of_limit terminations and their __init__.pyi exports: were a NaN guard for the Newton body_lin_vel runaway when base_com was unguarded. With the preset(newton=None) gate on base_com, the runaway no longer occurs and the guards are unused. - terrain_generator.py subdivided flat-grid border: was a workaround for Newton triangle-collision failures on the box-primitive border. Newton has since improved triangle handling, so the workaround is no longer needed. Co-authored-by: Octi Zhang --- .../velocity/config/anymal_d/rough_env_cfg.py | 35 +++++---- .../locomotion/velocity/velocity_env_cfg.py | 74 +++++++++---------- 2 files changed, 58 insertions(+), 51 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py index 38d6b9d0546e..772e4575ce77 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py @@ -3,13 +3,13 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg +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.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg from isaaclab_tasks.utils import PresetCfg ## @@ -19,20 +19,27 @@ @configclass -class AnymalDPhysxEventsCfg(EventsCfg, StartupEventsCfg): - pass - - -@configclass -class AnymalDEventsCfg(PresetCfg): - default = AnymalDPhysxEventsCfg() - newton = EventsCfg() +class RoughPhysicsCfg(PresetCfg): + default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15) + newton = NewtonCfg( + solver_cfg=MJWarpSolverCfg( + njmax=200, + nconmax=100, + cone="pyramidal", + impratio=1.0, + integrator="implicitfast", + use_mujoco_contacts=False, + ), + collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000), + num_substeps=1, + debug_mode=False, + ) physx = default @configclass class AnymalDRoughEnvCfg(LocomotionVelocityRoughEnvCfg): - events: AnymalDEventsCfg = AnymalDEventsCfg() + sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg()) def __post_init__(self): # post init of parent diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py index 81f38e756975..6217d1db8df4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -27,7 +27,7 @@ from isaaclab.utils.noise import UniformNoiseCfg as Unoise import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp -from isaaclab_tasks.utils import PresetCfg +from isaaclab_tasks.utils import PresetCfg, preset ## # Pre-defined configs @@ -161,6 +161,41 @@ def __post_init__(self): class EventsCfg: """Configuration for events.""" + # startup + physics_material = EventTerm( + func=mdp.randomize_rigid_body_material, + mode="startup", + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=".*"), + "static_friction_range": (0.8, 0.8), + "dynamic_friction_range": (0.6, 0.6), + "restitution_range": (0.0, 0.0), + "num_buckets": 64, + }, + ) + + add_base_mass = EventTerm( + func=mdp.randomize_rigid_body_mass, + mode="startup", + params={ + "asset_cfg": SceneEntityCfg("robot", body_names="base"), + "mass_distribution_params": (-5.0, 5.0), + "operation": "add", + }, + ) + + base_com = preset( + default=EventTerm( + func=mdp.randomize_rigid_body_com, + mode="startup", + params={ + "asset_cfg": SceneEntityCfg("robot", body_names="base"), + "com_range": {"x": (-0.05, 0.05), "y": (-0.05, 0.05), "z": (-0.01, 0.01)}, + }, + ), + newton=None, + ) + # reset base_external_force_torque = EventTerm( func=mdp.apply_external_force_torque, @@ -206,41 +241,6 @@ class EventsCfg: ) -@configclass -class StartupEventsCfg: - # startup - physics_material = EventTerm( - func=mdp.randomize_rigid_body_material, - mode="startup", - params={ - "asset_cfg": SceneEntityCfg("robot", body_names=".*"), - "static_friction_range": (0.8, 0.8), - "dynamic_friction_range": (0.6, 0.6), - "restitution_range": (0.0, 0.0), - "num_buckets": 64, - }, - ) - - add_base_mass = EventTerm( - func=mdp.randomize_rigid_body_mass, - mode="startup", - params={ - "asset_cfg": SceneEntityCfg("robot", body_names="base"), - "mass_distribution_params": (-5.0, 5.0), - "operation": "add", - }, - ) - - base_com = EventTerm( - func=mdp.randomize_rigid_body_com, - mode="startup", - params={ - "asset_cfg": SceneEntityCfg("robot", body_names="base"), - "com_range": {"x": (-0.05, 0.05), "y": (-0.05, 0.05), "z": (-0.01, 0.01)}, - }, - ) - - @configclass class RewardsCfg: """Reward terms for the MDP.""" @@ -313,7 +313,7 @@ class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg): # MDP settings rewards: RewardsCfg = RewardsCfg() terminations: TerminationsCfg = TerminationsCfg() - events: EventsCfg = MISSING + events: EventsCfg = EventsCfg() curriculum: CurriculumCfg = CurriculumCfg() def __post_init__(self): From 7ae07b76c0ee32ca1f3f93aa24dc50814dece66b Mon Sep 17 00:00:00 2001 From: hujc Date: Fri, 24 Apr 2026 04:10:20 +0000 Subject: [PATCH 3/5] Enable rough terrain on all locomotion envs with shared NewtonShapeCfg MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 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 #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 --- source/isaaclab_newton/config/extension.toml | 2 +- source/isaaclab_newton/docs/CHANGELOG.rst | 19 +++++++ .../isaaclab_newton/physics/__init__.pyi | 2 + .../isaaclab_newton/physics/newton_manager.py | 17 +++++- .../physics/newton_manager_cfg.py | 31 ++++++++++ source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 30 ++++++++++ .../velocity/config/a1/rough_env_cfg.py | 51 +++-------------- .../velocity/config/anymal_b/rough_env_cfg.py | 22 +------ .../velocity/config/anymal_c/rough_env_cfg.py | 23 +------- .../velocity/config/anymal_d/rough_env_cfg.py | 25 -------- .../velocity/config/cassie/rough_env_cfg.py | 45 ++------------- .../velocity/config/digit/rough_env_cfg.py | 49 +++++++--------- .../velocity/config/g1/rough_env_cfg.py | 45 ++------------- .../velocity/config/go1/rough_env_cfg.py | 53 +++-------------- .../velocity/config/go2/rough_env_cfg.py | 57 +------------------ .../velocity/config/h1/rough_env_cfg.py | 45 ++------------- .../locomotion/velocity/velocity_env_cfg.py | 43 +++++++++++++- source/isaaclab_tasks/test/test_hydra.py | 16 ++++++ 19 files changed, 217 insertions(+), 360 deletions(-) diff --git a/source/isaaclab_newton/config/extension.toml b/source/isaaclab_newton/config/extension.toml index 7d5691efdeb4..4329d2cd516f 100644 --- a/source/isaaclab_newton/config/extension.toml +++ b/source/isaaclab_newton/config/extension.toml @@ -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" diff --git a/source/isaaclab_newton/docs/CHANGELOG.rst b/source/isaaclab_newton/docs/CHANGELOG.rst index ec1f45bec732..03b9cee123a0 100644 --- a/source/isaaclab_newton/docs/CHANGELOG.rst +++ b/source/isaaclab_newton/docs/CHANGELOG.rst @@ -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) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_newton/isaaclab_newton/physics/__init__.pyi b/source/isaaclab_newton/isaaclab_newton/physics/__init__.pyi index 1b18da3838e1..a886d441d7c6 100644 --- a/source/isaaclab_newton/isaaclab_newton/physics/__init__.pyi +++ b/source/isaaclab_newton/isaaclab_newton/physics/__init__.pyi @@ -10,6 +10,7 @@ __all__ = [ "NewtonCfg", "NewtonCollisionPipelineCfg", "NewtonManager", + "NewtonShapeCfg", "NewtonSolverCfg", "XPBDSolverCfg", ] @@ -20,6 +21,7 @@ from .newton_manager_cfg import ( FeatherstoneSolverCfg, MJWarpSolverCfg, NewtonCfg, + NewtonShapeCfg, NewtonSolverCfg, XPBDSolverCfg, ) diff --git a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py index 8a752c8d4c8e..948a15dcc772 100644 --- a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py +++ b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager.py @@ -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 @@ -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 diff --git a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py index 942a6dc2f49d..047c20df6daf 100644 --- a/source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py +++ b/source/isaaclab_newton/isaaclab_newton/physics/newton_manager_cfg.py @@ -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. @@ -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. + """ diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index 81334689ea9f..c5caa8a6a340 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "1.5.24" +version = "1.5.25" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index c81768405791..07332d147d57 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,36 @@ Changelog --------- +1.5.25 (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.24 (2026-04-22) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/a1/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/a1/rough_env_cfg.py index 6ee9dbe78505..2857d3dc0341 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/a1/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/a1/rough_env_cfg.py @@ -3,14 +3,10 @@ # # 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 @@ -18,46 +14,8 @@ 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__() @@ -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 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py index aa67be58fc73..cf3fc2c3f232 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py @@ -3,14 +3,10 @@ # # 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 @@ -18,22 +14,8 @@ 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__() diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py index f8c24666ae2e..196c2eb6d126 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py @@ -3,14 +3,11 @@ # # 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 @@ -18,22 +15,8 @@ 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__() diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py index 772e4575ce77..c1c49677e66a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py @@ -3,14 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg -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 LocomotionVelocityRoughEnvCfg -from isaaclab_tasks.utils import PresetCfg ## # Pre-defined configs @@ -18,29 +14,8 @@ 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) - newton = NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=200, - nconmax=100, - cone="pyramidal", - impratio=1.0, - integrator="implicitfast", - use_mujoco_contacts=False, - ), - collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000), - num_substeps=1, - debug_mode=False, - ) - physx = default - - @configclass class AnymalDRoughEnvCfg(LocomotionVelocityRoughEnvCfg): - sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg()) - def __post_init__(self): # post init of parent super().__post_init__() diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/cassie/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/cassie/rough_env_cfg.py index 5bd6ba28684f..3436fee7c108 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/cassie/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/cassie/rough_env_cfg.py @@ -3,18 +3,16 @@ # # SPDX-License-Identifier: BSD-3-Clause + from isaaclab.managers import RewardTermCfg as RewTerm from isaaclab.managers import SceneEntityCfg from isaaclab.utils import configclass import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import ( - EventsCfg, LocomotionVelocityRoughEnvCfg, RewardsCfg, - StartupEventsCfg, ) -from isaaclab_tasks.utils import PresetCfg ## # Pre-defined configs @@ -52,47 +50,11 @@ class CassieRewardsCfg(RewardsCfg): ) -@configclass -class CassieNewtonEventsCfg(EventsCfg): - def __post_init__(self): - super().__post_init__() - self.push_robot = None - self.reset_robot_joints.params["position_range"] = (1.0, 1.0) - self.base_external_force_torque.params["asset_cfg"].body_names = [".*pelvis"] - 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 CassiePhysxEventsCfg(CassieNewtonEventsCfg, StartupEventsCfg): - def __post_init__(self): - super().__post_init__() - self.add_base_mass = None - self.base_com = None - - -@configclass -class CassieEventsCfg(PresetCfg): - default = CassiePhysxEventsCfg() - newton = CassieNewtonEventsCfg() - physx = default - - @configclass class CassieRoughEnvCfg(LocomotionVelocityRoughEnvCfg): """Cassie rough environment configuration.""" rewards: CassieRewardsCfg = CassieRewardsCfg() - events: CassieEventsCfg = CassieEventsCfg() def __post_init__(self): super().__post_init__() @@ -100,6 +62,11 @@ def __post_init__(self): self.scene.robot = CASSIE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/pelvis" + # Cassie uses "pelvis" as base body — disable mass randomization for bipeds + self.events.add_base_mass = None + self.events.base_com = None + self.events.base_external_force_torque.params["asset_cfg"].body_names = ".*pelvis" + # actions self.actions.joint_pos.scale = 0.5 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py index 185e9019a7c1..89f6647a24f6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py @@ -5,17 +5,13 @@ import math +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.managers import ObservationGroupCfg, ObservationTermCfg, RewardTermCfg, SceneEntityCfg, TerminationTermCfg from isaaclab.utils import configclass from isaaclab.utils.noise import UniformNoiseCfg as Unoise import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp -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 from isaaclab_assets.robots.agility import ARM_JOINT_NAMES, DIGIT_V4_CFG, LEG_JOINT_NAMES @@ -213,36 +209,12 @@ class DigitActionsCfg: ) -@configclass -class DigitNewtonEventsCfg(EventsCfg): - def __post_init__(self): - super().__post_init__() - self.base_external_force_torque.params["asset_cfg"] = SceneEntityCfg("robot", body_names="torso_base") - self.reset_robot_joints.params["position_range"] = (1.0, 1.0) - - -@configclass -class DigitPhysxEventsCfg(DigitNewtonEventsCfg, StartupEventsCfg): - def __post_init__(self): - super().__post_init__() - self.add_base_mass.params["asset_cfg"] = SceneEntityCfg("robot", body_names="torso_base") - self.base_com = None - - -@configclass -class DigitEventsCfg(PresetCfg): - default = DigitPhysxEventsCfg() - newton = DigitNewtonEventsCfg() - physx = default - - @configclass class DigitRoughEnvCfg(LocomotionVelocityRoughEnvCfg): rewards: DigitRewards = DigitRewards() observations: DigitObservations = DigitObservations() terminations: DigitTerminationsCfg = DigitTerminationsCfg() actions: DigitActionsCfg = DigitActionsCfg() - events: DigitEventsCfg = DigitEventsCfg() def __post_init__(self): super().__post_init__() @@ -256,6 +228,23 @@ def __post_init__(self): self.scene.contact_forces.update_period = self.sim.dt self.scene.height_scanner.update_period = self.decimation * self.sim.dt + # Digit uses "torso_base" as base body + self.events.add_base_mass.params["asset_cfg"].body_names = "torso_base" + self.events.base_external_force_torque.params["asset_cfg"].body_names = "torso_base" + self.events.base_com.default.params["asset_cfg"].body_names = "torso_base" + + # Override actuator to target only actuated joints. Digit has ball joints (rod constraints) + # that MuJoCo represents with 4 DoFs instead of 3, inflating joint_pos to 74 columns while + # joint_pos_target stays at 64. Using ".*" gives slice(None) which indexes both buffers + # differently. Explicit joint names produce a concrete index tensor that works correctly. + self.scene.robot.actuators = { + "legs_arms": ImplicitActuatorCfg( + joint_names_expr=LEG_JOINT_NAMES + ARM_JOINT_NAMES, + stiffness=None, + damping=None, + ), + } + # Commands self.commands.base_velocity.ranges.lin_vel_x = (-0.8, 0.8) self.commands.base_velocity.ranges.lin_vel_y = (-0.5, 0.5) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py index 6a7035416ab3..a24379a1553d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/g1/rough_env_cfg.py @@ -3,18 +3,16 @@ # # SPDX-License-Identifier: BSD-3-Clause + from isaaclab.managers import RewardTermCfg as RewTerm from isaaclab.managers import SceneEntityCfg from isaaclab.utils import configclass import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import ( - EventsCfg, LocomotionVelocityRoughEnvCfg, RewardsCfg, - StartupEventsCfg, ) -from isaaclab_tasks.utils import PresetCfg ## # Pre-defined configs @@ -106,45 +104,9 @@ class G1Rewards(RewardsCfg): ) -@configclass -class G1NewtonEventsCfg(EventsCfg): - def __post_init__(self): - super().__post_init__() - self.push_robot = None - self.reset_robot_joints.params["position_range"] = (1.0, 1.0) - self.base_external_force_torque.params["asset_cfg"].body_names = ["torso_link"] - 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 G1PhysxEventsCfg(G1NewtonEventsCfg, StartupEventsCfg): - def __post_init__(self): - super().__post_init__() - self.add_base_mass = None - self.base_com = None - - -@configclass -class G1EventsCfg(PresetCfg): - default = G1PhysxEventsCfg() - newton = G1NewtonEventsCfg() - physx = default - - @configclass class G1RoughEnvCfg(LocomotionVelocityRoughEnvCfg): rewards: G1Rewards = G1Rewards() - events: G1EventsCfg = G1EventsCfg() def __post_init__(self): # post init of parent @@ -153,6 +115,11 @@ def __post_init__(self): self.scene.robot = G1_MINIMAL_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_link" + # G1 uses "torso_link" as base body — disable mass randomization for bipeds + self.events.add_base_mass = None + self.events.base_com = None + self.events.base_external_force_torque.params["asset_cfg"].body_names = "torso_link" + # Rewards self.rewards.lin_vel_z_l2.weight = 0.0 self.rewards.undesired_contacts = None diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py index eafd3da45f30..35de20f038fe 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py @@ -3,14 +3,11 @@ # # 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 +from isaaclab_tasks.utils import preset ## # Pre-defined configs @@ -18,57 +15,25 @@ from isaaclab_assets.robots.unitree import UNITREE_GO1_CFG # isort: skip -@configclass -class Go1NewtonEventsCfg(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 Go1PhysxEventsCfg(Go1NewtonEventsCfg, 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 Go1EventsCfg(PresetCfg): - default = Go1PhysxEventsCfg() - newton = Go1NewtonEventsCfg() - physx = default - - @configclass class UnitreeGo1RoughEnvCfg(LocomotionVelocityRoughEnvCfg): - events: Go1EventsCfg = Go1EventsCfg() - def __post_init__(self): # post init of parent super().__post_init__() self.scene.robot = UNITREE_GO1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + self.scene.robot.actuators["base_legs"].armature = preset(default=0.0, newton=0.02) self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/trunk" # scale down the terrains because the robot is small self.scene.terrain.terrain_generator.sub_terrains["boxes"].grid_height_range = (0.025, 0.1) 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 + # Go1 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 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py index 40fbef99e27e..7dc068a29b53 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/go2/rough_env_cfg.py @@ -3,24 +3,11 @@ # # SPDX-License-Identifier: BSD-3-Clause -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 - - -@configclass -class PhysicsCfg(PresetCfg): - default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15) - physx = default - +from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg +from isaaclab_tasks.utils import preset ## # Pre-defined configs @@ -28,52 +15,14 @@ class PhysicsCfg(PresetCfg): from isaaclab_assets.robots.unitree import UNITREE_GO2_CFG # isort: skip -@configclass -class Go2NewtonEventsCfg(EventsCfg): - def __post_init__(self): - super().__post_init__() - self.push_robot = None - self.base_external_force_torque.params["asset_cfg"].body_names = "base" - 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 Go2PhysxEventsCfg(Go2NewtonEventsCfg, 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 = "base" - self.base_com = None - - -@configclass -class Go2EventsCfg(PresetCfg): - default = Go2PhysxEventsCfg() - newton = Go2NewtonEventsCfg() - physx = default - - @configclass class UnitreeGo2RoughEnvCfg(LocomotionVelocityRoughEnvCfg): - sim: SimulationCfg = SimulationCfg(physics=PhysicsCfg()) - events: Go2EventsCfg = Go2EventsCfg() - def __post_init__(self): # post init of parent super().__post_init__() self.scene.robot = UNITREE_GO2_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + self.scene.robot.actuators["base_legs"].armature = preset(default=0.0, newton=0.02) self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/base" # scale down the terrains because the robot is small self.scene.terrain.terrain_generator.sub_terrains["boxes"].grid_height_range = (0.025, 0.1) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/h1/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/h1/rough_env_cfg.py index 496aa4007fef..7d1ef73a5587 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/h1/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/h1/rough_env_cfg.py @@ -3,18 +3,16 @@ # # SPDX-License-Identifier: BSD-3-Clause + from isaaclab.managers import RewardTermCfg as RewTerm from isaaclab.managers import SceneEntityCfg from isaaclab.utils import configclass import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import ( - EventsCfg, LocomotionVelocityRoughEnvCfg, RewardsCfg, - StartupEventsCfg, ) -from isaaclab_tasks.utils import PresetCfg ## # Pre-defined configs @@ -73,45 +71,9 @@ class H1Rewards(RewardsCfg): ) -@configclass -class H1NewtonEventsCfg(EventsCfg): - def __post_init__(self): - super().__post_init__() - self.push_robot = None - self.reset_robot_joints.params["position_range"] = (1.0, 1.0) - self.base_external_force_torque.params["asset_cfg"].body_names = [".*torso_link"] - 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 H1PhysxEventsCfg(H1NewtonEventsCfg, StartupEventsCfg): - def __post_init__(self): - super().__post_init__() - self.add_base_mass = None - self.base_com = None - - -@configclass -class H1EventsCfg(PresetCfg): - default = H1PhysxEventsCfg() - newton = H1NewtonEventsCfg() - physx = default - - @configclass class H1RoughEnvCfg(LocomotionVelocityRoughEnvCfg): rewards: H1Rewards = H1Rewards() - events: H1EventsCfg = H1EventsCfg() def __post_init__(self): # post init of parent @@ -121,6 +83,11 @@ def __post_init__(self): if self.scene.height_scanner: self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_link" + # H1 uses "torso_link" as base body — disable mass randomization for bipeds + self.events.add_base_mass = None + self.events.base_com = None + self.events.base_external_force_torque.params["asset_cfg"].body_names = ".*torso_link" + # Rewards self.rewards.undesired_contacts = None self.rewards.flat_orientation_l2.weight = -1.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py index 6217d1db8df4..56e2e52fe8bc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -6,7 +6,9 @@ import math from dataclasses import MISSING +from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg, NewtonShapeCfg from isaaclab_newton.sensors import ContactSensorCfg as NewtonContactSensorCfg +from isaaclab_physx.physics import PhysxCfg from isaaclab_physx.sensors import ContactSensorCfg as PhysXContactSensorCfg import isaaclab.sim as sim_utils @@ -21,6 +23,7 @@ from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg from isaaclab.sensors import RayCasterCfg, patterns +from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR @@ -35,6 +38,36 @@ from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort: skip +## +# Physics presets +## + + +@configclass +class RoughPhysicsCfg(PresetCfg): + """Shared physics preset for all rough-terrain locomotion envs.""" + + default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15) + newton = NewtonCfg( + solver_cfg=MJWarpSolverCfg( + njmax=200, + nconmax=100, + cone="pyramidal", + impratio=1.0, + integrator="implicitfast", + use_mujoco_contacts=False, + ), + collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000), + num_substeps=1, + debug_mode=False, + # 1 cm shape margin is the single most important Newton setting for rough + # terrain — without it, non-Anymal-D robots fail to learn stable contact + # on triangle-mesh terrain. See isaaclab_newton 0.5.22 changelog. + default_shape_cfg=NewtonShapeCfg(margin=0.01), + ) + physx = default + + ## # Scene definition ## @@ -179,8 +212,12 @@ class EventsCfg: mode="startup", params={ "asset_cfg": SceneEntityCfg("robot", body_names="base"), - "mass_distribution_params": (-5.0, 5.0), - "operation": "add", + # Multiplicative ±25% log-uniform. Scale-invariant across robot sizes + # (no per-robot kg overrides needed) with geometric mean 1.0 and + # symmetric inverse perturbation (acceleration symmetric around nominal). + "mass_distribution_params": (1 / 1.25, 1.25), + "operation": "scale", + "distribution": "log_uniform", }, ) @@ -304,6 +341,8 @@ class CurriculumCfg: class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg): """Configuration for the locomotion velocity-tracking environment.""" + # Simulation settings — shared physics preset (PhysX + Newton) for all rough-terrain envs + sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg()) # Scene settings scene: MySceneCfg = MySceneCfg(num_envs=4096, env_spacing=2.5) # Basic settings diff --git a/source/isaaclab_tasks/test/test_hydra.py b/source/isaaclab_tasks/test/test_hydra.py index 098ba0732fdc..a7928ca3ff75 100644 --- a/source/isaaclab_tasks/test/test_hydra.py +++ b/source/isaaclab_tasks/test/test_hydra.py @@ -737,6 +737,22 @@ class EnvCfgFactory: assert presets["robot.actuators.legs.armature"]["physx"] == 0.0 +# ============================================================================= +# Tests: rough terrain config regressions +# ============================================================================= + + +def test_go1_rough_newton_armature_preset(): + """Go1 rough terrain uses higher Newton armature without changing PhysX.""" + from isaaclab_tasks.manager_based.locomotion.velocity.config.go1.rough_env_cfg import UnitreeGo1RoughEnvCfg + + env_cfg, _ = _apply(UnitreeGo1RoughEnvCfg(), global_presets=["newton"]) + assert env_cfg.scene.robot.actuators["base_legs"].armature == 0.02 + + env_cfg, _ = _apply(UnitreeGo1RoughEnvCfg()) + assert env_cfg.scene.robot.actuators["base_legs"].armature == 0.0 + + # ============================================================================= # Tests: PresetCfg inside deeply nested dicts (e.g., event term params) # ============================================================================= From 2dba57d73bb74bd8e2881aa97512a2b05187f08d Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Sat, 25 Apr 2026 10:29:52 -0700 Subject: [PATCH 4/5] Bump version to 1.5.26 Signed-off-by: Kelly Guo --- source/isaaclab_tasks/config/extension.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index c5caa8a6a340..c1c79a9b1e22 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "1.5.25" +version = "1.5.26" # Description title = "Isaac Lab Environments" From ac89bada8940c84bccb592e1ead5ae018e003af0 Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Sat, 25 Apr 2026 23:47:43 -0700 Subject: [PATCH 5/5] Update CHANGELOG with new features and changes Signed-off-by: Kelly Guo --- source/isaaclab_tasks/docs/CHANGELOG.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index fa2dd274cde3..54502c8a8354 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -19,7 +19,7 @@ Added 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 ^^^^^^^