Skip to content

Commit 2dfe033

Browse files
committed
Enable all rough terrain envs on Newton backend
Add RoughPhysicsCfg(PresetCfg) with Newton solver settings to all 9 non-Anymal-D rough terrain env configs. Remove broken StartupEventsCfg inheritance and move event customizations to __post_init__. Newton solver config (shared across all robots): - pyramidal friction cone, njmax=200, nconmax=100 - implicitfast integrator, max_triangle_pairs=2.5M - Newton collision pipeline (use_mujoco_contacts=False) Digit-specific fixes for MuJoCo ball-joint DoF inflation: - Split actuator config to explicit LEG+ARM joint names - Use exact body names in feet_slide reward Add batch test script (scripts/test_rough_envs_newton.sh) for running all rough envs sequentially in tmux.
1 parent 16c7abd commit 2dfe033

10 files changed

Lines changed: 324 additions & 294 deletions

File tree

scripts/test_rough_envs_newton.sh

Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
#!/usr/bin/env bash
2+
# Test all rough terrain envs on Newton backend.
3+
# Designed to run inside tmux so it survives disconnection.
4+
#
5+
# Usage:
6+
# tmux new -s rough-test
7+
# bash scripts/test_rough_envs_newton.sh [NUM_ENVS] [MAX_ITERS]
8+
# # Ctrl-b d to detach; tmux attach -t rough-test to reconnect
9+
set -euo pipefail
10+
11+
REPO_ROOT="$(cd "$(dirname "${BASH_SOURCE[0]}")/.." && pwd)"
12+
TRAIN_SCRIPT="scripts/reinforcement_learning/rsl_rl/train.py"
13+
NUM_ENVS="${1:-4096}"
14+
MAX_ITERS="${2:-50}"
15+
TIMESTAMP="$(date +%Y%m%d_%H%M%S)"
16+
LOG_DIR="${REPO_ROOT}/logs/rough_newton_test_${TIMESTAMP}"
17+
mkdir -p "${LOG_DIR}"
18+
19+
ROUGH_ENVS=(
20+
"Isaac-Velocity-Rough-Anymal-D-v0"
21+
"Isaac-Velocity-Rough-Anymal-B-v0"
22+
"Isaac-Velocity-Rough-Anymal-C-v0"
23+
"Isaac-Velocity-Rough-Unitree-A1-v0"
24+
"Isaac-Velocity-Rough-Unitree-Go1-v0"
25+
"Isaac-Velocity-Rough-Unitree-Go2-v0"
26+
"Isaac-Velocity-Rough-H1-v0"
27+
"Isaac-Velocity-Rough-G1-v0"
28+
"Isaac-Velocity-Rough-Cassie-v0"
29+
# "Isaac-Velocity-Rough-Digit-v0" # Skipped: ball-joint DoF mismatch (pre-existing Newton issue)
30+
)
31+
32+
TOTAL="${#ROUGH_ENVS[@]}"
33+
PASS=0
34+
FAIL=0
35+
RESULTS_FILE="${LOG_DIR}/summary.txt"
36+
37+
echo "========================================" | tee "${RESULTS_FILE}"
38+
echo " Rough Terrain Newton Test Suite" | tee -a "${RESULTS_FILE}"
39+
echo " $(date)" | tee -a "${RESULTS_FILE}"
40+
echo " Envs: ${TOTAL} NumEnvs: ${NUM_ENVS} MaxIters: ${MAX_ITERS}" | tee -a "${RESULTS_FILE}"
41+
echo "========================================" | tee -a "${RESULTS_FILE}"
42+
echo "" | tee -a "${RESULTS_FILE}"
43+
44+
for i in "${!ROUGH_ENVS[@]}"; do
45+
TASK="${ROUGH_ENVS[$i]}"
46+
IDX=$((i + 1))
47+
LOG_FILE="${LOG_DIR}/${TASK}.log"
48+
49+
echo "[${IDX}/${TOTAL}] Testing: ${TASK}" | tee -a "${RESULTS_FILE}"
50+
echo " Log: ${LOG_FILE}" | tee -a "${RESULTS_FILE}"
51+
52+
START_TIME="$(date +%s)"
53+
54+
if conda run -n env_isaaclab_develop python \
55+
"${REPO_ROOT}/${TRAIN_SCRIPT}" \
56+
--task "${TASK}" \
57+
--num_envs "${NUM_ENVS}" \
58+
--max_iterations "${MAX_ITERS}" \
59+
--headless \
60+
presets=newton \
61+
> "${LOG_FILE}" 2>&1; then
62+
STATUS="PASS"
63+
PASS=$((PASS + 1))
64+
else
65+
STATUS="FAIL (exit=$?)"
66+
FAIL=$((FAIL + 1))
67+
fi
68+
69+
END_TIME="$(date +%s)"
70+
ELAPSED=$((END_TIME - START_TIME))
71+
72+
echo " Result: ${STATUS} (${ELAPSED}s)" | tee -a "${RESULTS_FILE}"
73+
echo "" | tee -a "${RESULTS_FILE}"
74+
done
75+
76+
echo "========================================" | tee -a "${RESULTS_FILE}"
77+
echo " SUMMARY: ${PASS} passed, ${FAIL} failed out of ${TOTAL}" | tee -a "${RESULTS_FILE}"
78+
echo "========================================" | tee -a "${RESULTS_FILE}"
79+
echo ""
80+
echo "Full logs: ${LOG_DIR}"
81+
echo "Summary: ${RESULTS_FILE}"

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

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

6+
from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg
7+
from isaaclab_physx.physics import PhysxCfg
8+
9+
from isaaclab.sim import SimulationCfg
610
from isaaclab.utils import configclass
711

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

1515
##
@@ -19,44 +19,27 @@
1919

2020

2121
@configclass
22-
class A1NewtonEventsCfg(EventsCfg):
23-
def __post_init__(self):
24-
super().__post_init__()
25-
self.push_robot = None
26-
self.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
27-
self.reset_robot_joints.params["position_range"] = (1.0, 1.0)
28-
self.reset_base.params = {
29-
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
30-
"velocity_range": {
31-
"x": (0.0, 0.0),
32-
"y": (0.0, 0.0),
33-
"z": (0.0, 0.0),
34-
"roll": (0.0, 0.0),
35-
"pitch": (0.0, 0.0),
36-
"yaw": (0.0, 0.0),
37-
},
38-
}
39-
40-
41-
@configclass
42-
class A1PhysxEventsCfg(A1NewtonEventsCfg, StartupEventsCfg):
43-
def __post_init__(self):
44-
super().__post_init__()
45-
self.add_base_mass.params["mass_distribution_params"] = (-1.0, 3.0)
46-
self.add_base_mass.params["asset_cfg"].body_names = "trunk"
47-
self.base_com = None
48-
49-
50-
@configclass
51-
class A1EventsCfg(PresetCfg):
52-
default = A1PhysxEventsCfg()
53-
newton = A1NewtonEventsCfg()
22+
class RoughPhysicsCfg(PresetCfg):
23+
default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15)
24+
newton = NewtonCfg(
25+
solver_cfg=MJWarpSolverCfg(
26+
njmax=200,
27+
nconmax=100,
28+
cone="pyramidal",
29+
impratio=1.0,
30+
integrator="implicitfast",
31+
use_mujoco_contacts=False,
32+
),
33+
collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000),
34+
num_substeps=1,
35+
debug_mode=False,
36+
)
5437
physx = default
5538

5639

5740
@configclass
5841
class UnitreeA1RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
59-
events: A1EventsCfg = A1EventsCfg()
42+
sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg())
6043

6144
def __post_init__(self):
6245
# post init of parent
@@ -69,6 +52,11 @@ def __post_init__(self):
6952
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_range = (0.01, 0.06)
7053
self.scene.terrain.terrain_generator.sub_terrains["random_rough"].noise_step = 0.01
7154

55+
# A1 uses "trunk" as base body
56+
self.events.add_base_mass.params["asset_cfg"].body_names = "trunk"
57+
self.events.add_base_mass.params["mass_distribution_params"] = (-1.0, 3.0)
58+
self.events.base_external_force_torque.params["asset_cfg"].body_names = "trunk"
59+
7260
# reduce action scale
7361
self.actions.joint_pos.scale = 0.25
7462

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

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

6+
from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg
7+
from isaaclab_physx.physics import PhysxCfg
8+
9+
from isaaclab.sim import SimulationCfg
610
from isaaclab.utils import configclass
711

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

1515
##
@@ -19,20 +19,27 @@
1919

2020

2121
@configclass
22-
class AnymalBPhysxEventsCfg(EventsCfg, StartupEventsCfg):
23-
pass
24-
25-
26-
@configclass
27-
class AnymalBEventsCfg(PresetCfg):
28-
default = AnymalBPhysxEventsCfg()
29-
newton = EventsCfg()
22+
class RoughPhysicsCfg(PresetCfg):
23+
default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15)
24+
newton = NewtonCfg(
25+
solver_cfg=MJWarpSolverCfg(
26+
njmax=200,
27+
nconmax=100,
28+
cone="pyramidal",
29+
impratio=1.0,
30+
integrator="implicitfast",
31+
use_mujoco_contacts=False,
32+
),
33+
collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000),
34+
num_substeps=1,
35+
debug_mode=False,
36+
)
3037
physx = default
3138

3239

3340
@configclass
3441
class AnymalBRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
35-
events: AnymalBEventsCfg = AnymalBEventsCfg()
42+
sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg())
3643

3744
def __post_init__(self):
3845
# post init of parent

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

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

6+
from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg
7+
from isaaclab_physx.physics import PhysxCfg
8+
9+
from isaaclab.sim import SimulationCfg
610
from isaaclab.utils import configclass
711

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

1515
##
@@ -19,20 +19,27 @@
1919

2020

2121
@configclass
22-
class AnymalCPhysxEventsCfg(EventsCfg, StartupEventsCfg):
23-
pass
24-
25-
26-
@configclass
27-
class AnymalCEventsCfg(PresetCfg):
28-
default = AnymalCPhysxEventsCfg()
29-
newton = EventsCfg()
22+
class RoughPhysicsCfg(PresetCfg):
23+
default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15)
24+
newton = NewtonCfg(
25+
solver_cfg=MJWarpSolverCfg(
26+
njmax=200,
27+
nconmax=100,
28+
cone="pyramidal",
29+
impratio=1.0,
30+
integrator="implicitfast",
31+
use_mujoco_contacts=False,
32+
),
33+
collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000),
34+
num_substeps=1,
35+
debug_mode=False,
36+
)
3037
physx = default
3138

3239

3340
@configclass
3441
class AnymalCRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
35-
events: AnymalCEventsCfg = AnymalCEventsCfg()
42+
sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg())
3643

3744
def __post_init__(self):
3845
# post init of parent

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

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

6+
from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg
7+
from isaaclab_physx.physics import PhysxCfg
8+
69
from isaaclab.managers import RewardTermCfg as RewTerm
710
from isaaclab.managers import SceneEntityCfg
11+
from isaaclab.sim import SimulationCfg
812
from isaaclab.utils import configclass
913

1014
import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp
1115
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import (
12-
EventsCfg,
1316
LocomotionVelocityRoughEnvCfg,
1417
RewardsCfg,
15-
StartupEventsCfg,
1618
)
1719
from isaaclab_tasks.utils import PresetCfg
1820

@@ -22,6 +24,25 @@
2224
from isaaclab_assets.robots.cassie import CASSIE_CFG # isort: skip
2325

2426

27+
@configclass
28+
class RoughPhysicsCfg(PresetCfg):
29+
default = PhysxCfg(gpu_max_rigid_patch_count=10 * 2**15)
30+
newton = NewtonCfg(
31+
solver_cfg=MJWarpSolverCfg(
32+
njmax=200,
33+
nconmax=100,
34+
cone="pyramidal",
35+
impratio=1.0,
36+
integrator="implicitfast",
37+
use_mujoco_contacts=False,
38+
),
39+
collision_cfg=NewtonCollisionPipelineCfg(max_triangle_pairs=2_500_000),
40+
num_substeps=1,
41+
debug_mode=False,
42+
)
43+
physx = default
44+
45+
2546
@configclass
2647
class CassieRewardsCfg(RewardsCfg):
2748
termination_penalty = RewTerm(func=mdp.is_terminated, weight=-200.0)
@@ -52,54 +73,23 @@ class CassieRewardsCfg(RewardsCfg):
5273
)
5374

5475

55-
@configclass
56-
class CassieNewtonEventsCfg(EventsCfg):
57-
def __post_init__(self):
58-
super().__post_init__()
59-
self.push_robot = None
60-
self.reset_robot_joints.params["position_range"] = (1.0, 1.0)
61-
self.base_external_force_torque.params["asset_cfg"].body_names = [".*pelvis"]
62-
self.reset_base.params = {
63-
"pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
64-
"velocity_range": {
65-
"x": (0.0, 0.0),
66-
"y": (0.0, 0.0),
67-
"z": (0.0, 0.0),
68-
"roll": (0.0, 0.0),
69-
"pitch": (0.0, 0.0),
70-
"yaw": (0.0, 0.0),
71-
},
72-
}
73-
74-
75-
@configclass
76-
class CassiePhysxEventsCfg(CassieNewtonEventsCfg, StartupEventsCfg):
77-
def __post_init__(self):
78-
super().__post_init__()
79-
self.add_base_mass = None
80-
self.base_com = None
81-
82-
83-
@configclass
84-
class CassieEventsCfg(PresetCfg):
85-
default = CassiePhysxEventsCfg()
86-
newton = CassieNewtonEventsCfg()
87-
physx = default
88-
89-
9076
@configclass
9177
class CassieRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
9278
"""Cassie rough environment configuration."""
9379

80+
sim: SimulationCfg = SimulationCfg(physics=RoughPhysicsCfg())
9481
rewards: CassieRewardsCfg = CassieRewardsCfg()
95-
events: CassieEventsCfg = CassieEventsCfg()
9682

9783
def __post_init__(self):
9884
super().__post_init__()
9985
# scene
10086
self.scene.robot = CASSIE_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
10187
self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/pelvis"
10288

89+
# Cassie uses "pelvis" as base body — disable mass randomization for bipeds
90+
self.events.add_base_mass = None
91+
self.events.base_external_force_torque.params["asset_cfg"].body_names = ".*pelvis"
92+
10393
# actions
10494
self.actions.joint_pos.scale = 0.5
10595

0 commit comments

Comments
 (0)