From 4f1c3b2bb7533baa5e34593a50346c4922e07a0d Mon Sep 17 00:00:00 2001 From: jichuanh Date: Sun, 3 May 2026 07:09:38 +0000 Subject: [PATCH 1/2] Mirror stable structure in warp velocity envs Bring the warp locomotion velocity configs structurally in line with their stable counterparts so the two backends can share Newton tuning and avoid drift. velocity_env_cfg.py: - Mirror stable's nested ObservationsCfg.PolicyCfg layout. - Add EventsCfg.physics_material/add_base_mass/base_com slots (None until warp MDP gets randomize_rigid_body_material/_mass and a capture-safe randomize_rigid_body_com); slot names match stable so per-robot overrides can introspect them. - Replace the hand-rolled ContactSensorCfg with a Newton sensor preset built locally; values mirror stable's VelocityEnvContactSensorCfg.newton. - Set sim physics to a local ROUGH_NEWTON_CFG that mirrors stable's RoughPhysicsCfg.newton (njmax=200, nconmax=100, pyramidal cone, 2.5M triangle pairs, 1cm shape margin). Per-robot flat_env_cfg.py (a1, anymal_b/c/d, cassie, g1, go1/go2, h1): - Replace inline NewtonCfg with a local _FLAT_NEWTON_CFG whose values mirror the matching stable PhysicsCfg.newton. - Drop dead height_scanner=None / observations.policy.height_scan=None setters (warp env has no RayCaster). Per-robot rough_env_cfg.py (anymal_b/c, anymal_d, go1): - Drop redundant manager_call_max_mode={'Scene': 1} overrides; the cap is already enforced via ManagerCallSwitch.MAX_MODE_OVERRIDES. Why inlined instead of imported from stable: hydra_task_config resolves env cfgs before SimulationApp initialises Kit. Importing stable's RoughPhysicsCfg / per-robot PhysicsCfg chains through isaaclab_physx which 'from pxr import ...' at module load; early pxr loading leaves USD wrappers half-initialised and segfaults Kit during AppLauncher. Comments in each file flag the constraint and ask future edits to keep values in sync with stable. --- .../velocity/config/a1/flat_env_cfg.py | 27 ++-- .../velocity/config/anymal_b/flat_env_cfg.py | 27 ++-- .../velocity/config/anymal_b/rough_env_cfg.py | 8 +- .../velocity/config/anymal_c/flat_env_cfg.py | 23 ++- .../velocity/config/anymal_c/rough_env_cfg.py | 1 - .../velocity/config/anymal_d/flat_env_cfg.py | 30 ++-- .../velocity/config/anymal_d/rough_env_cfg.py | 8 +- .../velocity/config/cassie/flat_env_cfg.py | 22 ++- .../velocity/config/g1/flat_env_cfg.py | 22 ++- .../velocity/config/go1/flat_env_cfg.py | 22 ++- .../velocity/config/go1/rough_env_cfg.py | 1 - .../velocity/config/go2/flat_env_cfg.py | 22 ++- .../velocity/config/h1/flat_env_cfg.py | 22 ++- .../locomotion/velocity/velocity_env_cfg.py | 133 ++++++++++++------ 14 files changed, 193 insertions(+), 175 deletions(-) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/flat_env_cfg.py index b27f8098d629..ec46fb3b3010 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/flat_env_cfg.py @@ -10,25 +10,20 @@ from .rough_env_cfg import UnitreeA1RoughEnvCfg +# Mirror of stable Unitree A1 ``PhysicsCfg.newton``. Inlined to avoid importing +# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=60, nconmax=30, cone="pyramidal", impratio=1, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class UnitreeA1FlatEnvCfg(UnitreeA1RoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=60, - nconmax=30, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): - # post init of parent super().__post_init__() # override rewards @@ -38,16 +33,12 @@ def __post_init__(self): # change terrain to flat self.scene.terrain.terrain_type = "plane" self.scene.terrain.terrain_generator = None - # no height scan - # self.scene.height_scanner = None - # self.observations.policy.height_scan = None # no terrain curriculum self.curriculum.terrain_levels = None class UnitreeA1FlatEnvCfg_PLAY(UnitreeA1FlatEnvCfg): def __post_init__(self) -> None: - # post init of parent super().__post_init__() # make a smaller scene for play diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/flat_env_cfg.py index 28c0dc5c26b6..cc77ff097dab 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/flat_env_cfg.py @@ -10,25 +10,20 @@ from .rough_env_cfg import AnymalBRoughEnvCfg +# Mirror of stable Anymal-B ``PhysicsCfg.newton``. Inlined to avoid importing +# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=75, nconmax=15, cone="elliptic", impratio=100, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class AnymalBFlatEnvCfg(AnymalBRoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=75, - nconmax=15, - cone="elliptic", - impratio=100, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): - # post init of parent super().__post_init__() # override rewards @@ -38,16 +33,12 @@ def __post_init__(self): # change terrain to flat self.scene.terrain.terrain_type = "plane" self.scene.terrain.terrain_generator = None - # no height scan - self.scene.height_scanner = None - self.observations.policy.height_scan = None # no terrain curriculum self.curriculum.terrain_levels = None class AnymalBFlatEnvCfg_PLAY(AnymalBFlatEnvCfg): def __post_init__(self) -> None: - # post init of parent super().__post_init__() # make a smaller scene for play diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py index 9811356ef220..26986d3f83b9 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/rough_env_cfg.py @@ -15,20 +15,26 @@ class AnymalBRoughEnvCfg(LocomotionVelocityRoughEnvCfg): def __post_init__(self): super().__post_init__() self.scene.robot = ANYMAL_B_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") - self.manager_call_max_mode = {"Scene": 1} @configclass class AnymalBRoughEnvCfg_PLAY(AnymalBRoughEnvCfg): def __post_init__(self): super().__post_init__() + + # make a smaller scene for play self.scene.num_envs = 50 self.scene.env_spacing = 2.5 + # spawn the robot randomly in the grid (instead of their terrain levels) self.scene.terrain.max_init_terrain_level = None + # reduce the number of terrains to save memory if self.scene.terrain.terrain_generator is not None: self.scene.terrain.terrain_generator.num_rows = 5 self.scene.terrain.terrain_generator.num_cols = 5 self.scene.terrain.terrain_generator.curriculum = False + + # disable randomization for play self.observations.policy.enable_corruption = False + # remove random pushing event self.events.base_external_force_torque = None self.events.push_robot = None diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/flat_env_cfg.py index e82cf9559d61..053e8fa09bb7 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/flat_env_cfg.py @@ -10,25 +10,20 @@ from .rough_env_cfg import AnymalCRoughEnvCfg +# Mirror of stable Anymal-C ``PhysicsCfg.newton``. Inlined to avoid importing +# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=120, nconmax=15, cone="elliptic", impratio=100, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class AnymalCFlatEnvCfg(AnymalCRoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=120, - nconmax=15, - cone="elliptic", - impratio=100, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): - # post init of parent super().__post_init__() # override rewards diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py index 36af75613c07..a3664a3b1b15 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/rough_env_cfg.py @@ -21,7 +21,6 @@ def __post_init__(self): # switch robot to anymal-c self.scene.robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.robot.actuators["legs"].armature = 0.01 - self.manager_call_max_mode = {"Scene": 1} @configclass diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/flat_env_cfg.py index 1f98c1b56120..87a359644170 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/flat_env_cfg.py @@ -10,37 +10,43 @@ from .rough_env_cfg import AnymalDRoughEnvCfg +# Mirror of stable AnymalD ``PhysicsCfg.newton``. Inlined to avoid importing the +# stable ``PhysicsCfg`` (which would chain into ``isaaclab_physx`` and ``pxr`` at +# module-load time, before SimulationApp has initialised the Kit extensions). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=60, nconmax=25, cone="elliptic", impratio=100.0), + num_substeps=1, + debug_mode=False, +) + @configclass class AnymalDFlatEnvCfg(AnymalDRoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=60, - nconmax=25, - cone="elliptic", - impratio=100.0, - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): super().__post_init__() + + # override rewards self.rewards.flat_orientation_l2.weight = -5.0 self.rewards.dof_torques_l2.weight = -2.5e-5 self.rewards.feet_air_time.weight = 0.5 + # change terrain to flat self.scene.terrain.terrain_type = "plane" self.scene.terrain.terrain_generator = None + # no terrain curriculum self.curriculum.terrain_levels = None class AnymalDFlatEnvCfg_PLAY(AnymalDFlatEnvCfg): def __post_init__(self) -> None: super().__post_init__() + + # make a smaller scene for play self.scene.num_envs = 50 self.scene.env_spacing = 2.5 + # disable randomization for play self.observations.policy.enable_corruption = False + # remove random pushing event self.events.base_external_force_torque = None self.events.push_robot = None diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py index 1cafa006ee64..074edf915a9d 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/rough_env_cfg.py @@ -18,20 +18,26 @@ class AnymalDRoughEnvCfg(LocomotionVelocityRoughEnvCfg): def __post_init__(self): super().__post_init__() self.scene.robot = ANYMAL_D_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") - self.manager_call_max_mode = {"Scene": 1} @configclass class AnymalDRoughEnvCfg_PLAY(AnymalDRoughEnvCfg): def __post_init__(self): super().__post_init__() + + # make a smaller scene for play self.scene.num_envs = 50 self.scene.env_spacing = 2.5 + # spawn the robot randomly in the grid (instead of their terrain levels) self.scene.terrain.max_init_terrain_level = None + # reduce the number of terrains to save memory if self.scene.terrain.terrain_generator is not None: self.scene.terrain.terrain_generator.num_rows = 5 self.scene.terrain.terrain_generator.num_cols = 5 self.scene.terrain.terrain_generator.curriculum = False + + # disable randomization for play self.observations.policy.enable_corruption = False + # remove random pushing event self.events.base_external_force_torque = None self.events.push_robot = None diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/flat_env_cfg.py index bcc670cf3788..63638ef06a0b 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/flat_env_cfg.py @@ -10,22 +10,18 @@ from .rough_env_cfg import CassieRoughEnvCfg +# Mirror of stable Cassie ``PhysicsCfg.newton``. Inlined to avoid importing the +# stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=52, nconmax=15, cone="pyramidal", impratio=1, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class CassieFlatEnvCfg(CassieRoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=52, - nconmax=15, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): super().__post_init__() diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py index 3d9047a98506..57901327d29d 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/flat_env_cfg.py @@ -11,22 +11,18 @@ from .rough_env_cfg import G1RoughEnvCfg +# Mirror of stable G1 ``PhysicsCfg.newton``. Inlined to avoid importing the +# stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=95, nconmax=10, cone="pyramidal", impratio=1, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class G1FlatEnvCfg(G1RoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=95, - nconmax=10, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): super().__post_init__() diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/flat_env_cfg.py index e4fbc73e1d08..1d72bc482deb 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/flat_env_cfg.py @@ -10,22 +10,18 @@ from .rough_env_cfg import UnitreeGo1RoughEnvCfg +# Mirror of stable Unitree Go1 ``PhysicsCfg.newton``. Inlined to avoid importing +# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=60, nconmax=25, cone="pyramidal", impratio=1, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class UnitreeGo1FlatEnvCfg(UnitreeGo1RoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=60, - nconmax=25, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): super().__post_init__() diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py index 2864bbba3130..dae160012fb5 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/rough_env_cfg.py @@ -15,7 +15,6 @@ class UnitreeGo1RoughEnvCfg(LocomotionVelocityRoughEnvCfg): def __post_init__(self): super().__post_init__() self.scene.robot = UNITREE_GO1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") - self.manager_call_max_mode = {"Scene": 1} 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 diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/flat_env_cfg.py index ad8a8aa862f0..cba2c03aeb3d 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/flat_env_cfg.py @@ -10,22 +10,18 @@ from .rough_env_cfg import UnitreeGo2RoughEnvCfg +# Mirror of stable Unitree Go2 ``PhysicsCfg.newton``. Inlined to avoid importing +# the stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=65, nconmax=35, cone="pyramidal", impratio=1, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class UnitreeGo2FlatEnvCfg(UnitreeGo2RoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=65, - nconmax=35, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): super().__post_init__() diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/flat_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/flat_env_cfg.py index 22648c27a2c5..8f05ca7d6956 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/flat_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/flat_env_cfg.py @@ -10,22 +10,18 @@ from .rough_env_cfg import H1RoughEnvCfg +# Mirror of stable H1 ``PhysicsCfg.newton``. Inlined to avoid importing the +# stable preset (which chains into ``isaaclab_physx`` and ``pxr``). +_FLAT_NEWTON_CFG = NewtonCfg( + solver_cfg=MJWarpSolverCfg(njmax=65, nconmax=15, cone="pyramidal", impratio=1, integrator="implicitfast"), + num_substeps=1, + debug_mode=False, +) + @configclass class H1FlatEnvCfg(H1RoughEnvCfg): - sim: SimulationCfg = SimulationCfg( - physics=NewtonCfg( - solver_cfg=MJWarpSolverCfg( - njmax=65, - nconmax=15, - cone="pyramidal", - impratio=1, - integrator="implicitfast", - ), - num_substeps=1, - debug_mode=False, - ) - ) + sim: SimulationCfg = SimulationCfg(physics=_FLAT_NEWTON_CFG) def __post_init__(self): super().__post_init__() diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/velocity_env_cfg.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/velocity_env_cfg.py index 7442d3654ba3..e47fd2d3fb5a 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/velocity_env_cfg.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -10,6 +10,8 @@ from isaaclab_experimental.managers import RewardTermCfg as RewTerm from isaaclab_experimental.managers import SceneEntityCfg from isaaclab_experimental.managers import TerminationTermCfg as DoneTerm +from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg, NewtonShapeCfg +from isaaclab_newton.sensors import ContactSensorCfg as NewtonContactSensorCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg @@ -18,7 +20,7 @@ from isaaclab.managers import EventTermCfg as EventTerm from isaaclab.managers import ObservationGroupCfg as ObsGroup from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sensors import ContactSensorCfg +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 @@ -32,6 +34,42 @@ from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort: skip +## +# Physics preset +## + + +# Mirror of the ``newton`` field from +# :class:`isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg.RoughPhysicsCfg`. +# Inlined (instead of imported) because importing the stable preset transitively pulls +# in :mod:`isaaclab_physx` and ``pxr`` at module load time, and :func:`hydra_task_config` +# resolves env cfgs *before* :class:`SimulationApp` is initialised — early ``pxr`` loading +# leaves the USD extension wrappers half-initialised and crashes the Kit startup. +# Keep the values in sync with stable. +ROUGH_NEWTON_CFG = 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), +) + + +def _rough_contact_sensor_cfg() -> NewtonContactSensorCfg: + """Newton contact sensor preset matching stable's ``VelocityEnvContactSensorCfg.newton``.""" + return NewtonContactSensorCfg(prim_path="{ENV_REGEX_NS}/Robot/.*", history_length=3, track_air_time=True) + + ## # Scene definition ## @@ -64,12 +102,10 @@ class MySceneCfg(InteractiveSceneCfg): # robots robot: ArticulationCfg = MISSING # sensors - contact_forces = ContactSensorCfg( - prim_path="{ENV_REGEX_NS}/Robot/.*", - filter_prim_paths_expr=[], - history_length=3, - track_air_time=True, - ) + # height_scanner: omitted — RayCaster height-scan observation has no warp + # implementation yet. Per-robot rough configs that mirror stable will need a + # warp height-scan term once available. + contact_forces = _rough_contact_sensor_cfg() # lights sky_light = AssetBaseCfg( prim_path="/World/skyLight", @@ -110,50 +146,57 @@ class ActionsCfg: joint_pos = mdp.JointPositionActionCfg(asset_name="robot", joint_names=[".*"], scale=0.5, use_default_offset=True) -@configclass -class PolicyCfg(ObsGroup): - """Observations for policy group.""" - - # observation terms (order preserved) - base_lin_vel = ObsTerm(func=mdp.base_lin_vel, noise=Unoise(n_min=-0.1, n_max=0.1)) - base_ang_vel = ObsTerm(func=mdp.base_ang_vel, noise=Unoise(n_min=-0.2, n_max=0.2)) - projected_gravity = ObsTerm( - func=mdp.projected_gravity, - noise=Unoise(n_min=-0.05, n_max=0.05), - ) - velocity_commands = ObsTerm(func=mdp.generated_commands, params={"command_name": "base_velocity"}) - joint_pos = ObsTerm(func=mdp.joint_pos_rel, noise=Unoise(n_min=-0.01, n_max=0.01)) - joint_vel = ObsTerm(func=mdp.joint_vel_rel, noise=Unoise(n_min=-1.5, n_max=1.5)) - actions = ObsTerm(func=mdp.last_action) - - def __post_init__(self): - self.enable_corruption = True - self.concatenate_terms = True - - @configclass class ObservationsCfg: """Observation specifications for the MDP.""" + @configclass + class PolicyCfg(ObsGroup): + """Observations for policy group.""" + + # observation terms (order preserved) + base_lin_vel = ObsTerm(func=mdp.base_lin_vel, noise=Unoise(n_min=-0.1, n_max=0.1)) + base_ang_vel = ObsTerm(func=mdp.base_ang_vel, noise=Unoise(n_min=-0.2, n_max=0.2)) + projected_gravity = ObsTerm( + func=mdp.projected_gravity, + noise=Unoise(n_min=-0.05, n_max=0.05), + ) + velocity_commands = ObsTerm(func=mdp.generated_commands, params={"command_name": "base_velocity"}) + joint_pos = ObsTerm(func=mdp.joint_pos_rel, noise=Unoise(n_min=-0.01, n_max=0.01)) + joint_vel = ObsTerm(func=mdp.joint_vel_rel, noise=Unoise(n_min=-1.5, n_max=1.5)) + actions = ObsTerm(func=mdp.last_action) + # height_scan: no warp implementation yet (RayCaster + height_scan + # observation are torch-only). Field kept implicit via stable mirror — + # robot-level rough configs that mirror stable should set this to None. + + def __post_init__(self): + self.enable_corruption = True + self.concatenate_terms = True + # observation groups policy: PolicyCfg = PolicyCfg() @configclass -class EventCfg: - """Configuration for events.""" - - # FIXME(warp-migration): COM randomization in exp manager-based locomotion currently causes - # NaNs and is temporarily disabled. - # 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)}, - # }, - # ) +class EventsCfg: + """Configuration for events. + + Mirrors stable :class:`~isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg.EventsCfg` + field-for-field. Events without a warp MDP implementation are kept as + ``None`` so per-robot configs can introspect the field for parity with + stable, even if the warp manager skips them at runtime. + """ + + # startup — no warp MDP implementations yet; tracked as gaps. + physics_material = None + """Friction randomization. No warp ``randomize_rigid_body_material`` yet.""" + + add_base_mass = None + """Base-mass randomization. No warp ``randomize_rigid_body_mass`` yet.""" + base_com = None + """COM randomization. ``randomize_rigid_body_com`` exists in warp MDP but + currently disabled for locomotion envs (NaN under capture).""" # reset base_external_force_torque = EventTerm( @@ -263,6 +306,8 @@ class CurriculumCfg: class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg): """Configuration for the locomotion velocity-tracking environment.""" + # Simulation settings — Newton solver matched to stable's RoughPhysicsCfg.newton + sim: SimulationCfg = SimulationCfg(physics=ROUGH_NEWTON_CFG) # Scene settings scene: MySceneCfg = MySceneCfg(num_envs=4096, env_spacing=2.5, replicate_physics=True) # Basic settings @@ -272,7 +317,7 @@ class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg): # MDP settings rewards: RewardsCfg = RewardsCfg() terminations: TerminationsCfg = TerminationsCfg() - events: EventCfg = EventCfg() + events: EventsCfg = EventsCfg() curriculum: CurriculumCfg = CurriculumCfg() def __post_init__(self): @@ -281,13 +326,13 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.dt = 1.0 / 200.0 + self.sim.dt = 0.005 self.sim.render_interval = self.decimation self.sim.physics_material = self.scene.terrain.physics_material # update sensor update periods if self.scene.contact_forces is not None: self.scene.contact_forces.update_period = self.sim.dt - # check if terrain levels curriculum is enabled + # check if terrain levels curriculum is enabled — if so, enable curriculum for terrain generator if getattr(self.curriculum, "terrain_levels", None) is not None: if self.scene.terrain.terrain_generator is not None: self.scene.terrain.terrain_generator.curriculum = True From 1ecf2e9863c9a06171a9b9a7ec4acf3d5c345011 Mon Sep 17 00:00:00 2001 From: jichuanh Date: Sun, 3 May 2026 07:09:48 +0000 Subject: [PATCH 2/2] Enable warp Rough velocity registrations for all robots MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Register `Isaac-Velocity-Rough-{Robot}-Warp-v0` and `-Play-v0` for all 9 warp velocity robots. Rough was previously commented out for anymal_d/g1/h1 (pending isaaclab_physx availability, which has since landed) and missing entirely for the other 6 quadrupeds + Cassie. After this change there are 36 warp velocity envs registered (9 robots × Flat/Rough × regular/Play), matching the stable env's set. Each Rough registration reuses the corresponding stable rsl_rl / skrl / rl_games / rsl_rl_with_symmetry agent config entry points where they exist; warp envs share agent configs with stable so symmetry and network architecture stay in sync. --- .../locomotion/velocity/config/a1/__init__.py | 22 +++++++++ .../velocity/config/anymal_b/__init__.py | 28 +++++++++++ .../velocity/config/anymal_c/__init__.py | 30 ++++++++++++ .../velocity/config/anymal_d/__init__.py | 47 +++++++++---------- .../velocity/config/cassie/__init__.py | 22 +++++++++ .../locomotion/velocity/config/g1/__init__.py | 45 +++++++++--------- .../velocity/config/go1/__init__.py | 22 +++++++++ .../velocity/config/go2/__init__.py | 22 +++++++++ .../locomotion/velocity/config/h1/__init__.py | 44 ++++++++--------- 9 files changed, 212 insertions(+), 70 deletions(-) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/__init__.py index 6c79524e8532..b07cbaf1ea0d 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/a1/__init__.py @@ -35,3 +35,25 @@ "sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-Unitree-A1-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeA1RoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeA1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-Unitree-A1-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeA1RoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeA1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/__init__.py index cbbf5290e82a..bf1d28033430 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_b/__init__.py @@ -35,3 +35,31 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-Anymal-B-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalBRoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerCfg", + "rsl_rl_with_symmetry_cfg_entry_point": ( + f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerWithSymmetryCfg" + ), + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-Anymal-B-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalBRoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerCfg", + "rsl_rl_with_symmetry_cfg_entry_point": ( + f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalBRoughPPORunnerWithSymmetryCfg" + ), + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/__init__.py index 318b13cc4707..710c3a0c0088 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_c/__init__.py @@ -37,3 +37,33 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-Anymal-C-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalCRoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerCfg", + "rsl_rl_with_symmetry_cfg_entry_point": ( + f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerWithSymmetryCfg" + ), + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_rough_ppo_cfg.yaml", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-Anymal-C-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalCRoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerCfg", + "rsl_rl_with_symmetry_cfg_entry_point": ( + f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalCRoughPPORunnerWithSymmetryCfg" + ), + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_rough_ppo_cfg.yaml", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/__init__.py index e5e75d19dc2d..fcd909209c5e 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/anymal_d/__init__.py @@ -12,31 +12,6 @@ # Register Gym environments. ## -# Rough env disabled: requires isaaclab_physx which is not yet available on dev/newton. -# The package exists on upstream/develop (commit 308400f1d35) but has not been merged. -# Re-enable once dev/newton picks up isaaclab_physx. -# gym.register( -# id="Isaac-Velocity-Rough-Anymal-D-Warp-v0", -# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", -# disable_env_checker=True, -# kwargs={ -# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg", -# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg", -# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", -# }, -# ) - -# gym.register( -# id="Isaac-Velocity-Rough-Anymal-D-Warp-Play-v0", -# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", -# disable_env_checker=True, -# kwargs={ -# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg_PLAY", -# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg", -# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", -# }, -# ) - gym.register( id="Isaac-Velocity-Flat-Anymal-D-Warp-v0", entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", @@ -58,3 +33,25 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-Anymal-D-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-Anymal-D-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/__init__.py index 4d9d4a77883a..6eba6ddbc84e 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/cassie/__init__.py @@ -33,3 +33,25 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-Cassie-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:CassieRoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:CassieRoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-Cassie-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:CassieRoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:CassieRoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/__init__.py index 83bdf047a488..057e5ed6508e 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/g1/__init__.py @@ -12,29 +12,6 @@ # Register Gym environments. ## -# gym.register( -# id="Isaac-Velocity-Rough-G1-Warp-v0", -# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", -# disable_env_checker=True, -# kwargs={ -# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:G1RoughEnvCfg", -# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:G1RoughPPORunnerCfg", -# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", -# }, -# ) - - -# gym.register( -# id="Isaac-Velocity-Rough-G1-Warp-Play-v0", -# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", -# disable_env_checker=True, -# kwargs={ -# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:G1RoughEnvCfg_PLAY", -# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:G1RoughPPORunnerCfg", -# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", -# }, -# ) - gym.register( id="Isaac-Velocity-Flat-G1-Warp-v0", entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", @@ -56,3 +33,25 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-G1-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:G1RoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:G1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-G1-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:G1RoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:G1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/__init__.py index 038f55740728..e022c56e5d60 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go1/__init__.py @@ -33,3 +33,25 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-Unitree-Go1-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeGo1RoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeGo1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-Unitree-Go1-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeGo1RoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeGo1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/__init__.py index 7e124029c682..2d280138ddb1 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/go2/__init__.py @@ -33,3 +33,25 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-Unitree-Go2-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeGo2RoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeGo2RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-Unitree-Go2-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:UnitreeGo2RoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:UnitreeGo2RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/__init__.py b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/__init__.py index 95a1e8f29e3f..b00def062b67 100644 --- a/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/__init__.py +++ b/source/isaaclab_tasks_experimental/isaaclab_tasks_experimental/manager_based/locomotion/velocity/config/h1/__init__.py @@ -12,28 +12,6 @@ # Register Gym environments. ## -# gym.register( -# id="Isaac-Velocity-Rough-H1-Warp-v0", -# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", -# disable_env_checker=True, -# kwargs={ -# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1RoughEnvCfg", -# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1RoughPPORunnerCfg", -# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", -# }, -# ) - -# gym.register( -# id="Isaac-Velocity-Rough-H1-Warp-Play-v0", -# entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", -# disable_env_checker=True, -# kwargs={ -# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1RoughEnvCfg_PLAY", -# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1RoughPPORunnerCfg", -# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", -# }, -# ) - gym.register( id="Isaac-Velocity-Flat-H1-Warp-v0", entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", @@ -55,3 +33,25 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Velocity-Rough-H1-Warp-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1RoughEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Velocity-Rough-H1-Warp-Play-v0", + entry_point="isaaclab_experimental.envs:ManagerBasedRLEnvWarp", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1RoughEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1RoughPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml", + }, +)