Skip to content

Commit 614ea2d

Browse files
ooctipushujc7
authored andcommitted
Cherry-pick: Anymal-D rough terrain (subset) from isaac-sim#5225
Originally Octi's commit on PR isaac-sim#5225. Cherry-picked here so the rough terrain stack does not depend on his still-open WIP PR while he is away. Included from isaac-sim#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 newton-physics/newton#2332 will let us drop the gate once it ships in a release. Dropped from isaac-sim#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 <zhengyuz@nvidia.com>
1 parent fcfb8ac commit 614ea2d

2 files changed

Lines changed: 62 additions & 51 deletions

File tree

source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/anymal_d/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 AnymalDPhysxEventsCfg(EventsCfg, StartupEventsCfg):
23-
pass
24-
25-
26-
@configclass
27-
class AnymalDEventsCfg(PresetCfg):
28-
default = AnymalDPhysxEventsCfg()
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 AnymalDRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
35-
events: AnymalDEventsCfg = AnymalDEventsCfg()
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/velocity_env_cfg.py

Lines changed: 41 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
from isaaclab.utils.noise import UniformNoiseCfg as Unoise
2828

2929
import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp
30-
from isaaclab_tasks.utils import PresetCfg
30+
from isaaclab_tasks.utils import PresetCfg, preset
3131

3232
##
3333
# Pre-defined configs
@@ -161,6 +161,41 @@ def __post_init__(self):
161161
class EventsCfg:
162162
"""Configuration for events."""
163163

164+
# startup
165+
physics_material = EventTerm(
166+
func=mdp.randomize_rigid_body_material,
167+
mode="startup",
168+
params={
169+
"asset_cfg": SceneEntityCfg("robot", body_names=".*"),
170+
"static_friction_range": (0.8, 0.8),
171+
"dynamic_friction_range": (0.6, 0.6),
172+
"restitution_range": (0.0, 0.0),
173+
"num_buckets": 64,
174+
},
175+
)
176+
177+
add_base_mass = EventTerm(
178+
func=mdp.randomize_rigid_body_mass,
179+
mode="startup",
180+
params={
181+
"asset_cfg": SceneEntityCfg("robot", body_names="base"),
182+
"mass_distribution_params": (-5.0, 5.0),
183+
"operation": "add",
184+
},
185+
)
186+
187+
base_com = preset(
188+
default=EventTerm(
189+
func=mdp.randomize_rigid_body_com,
190+
mode="startup",
191+
params={
192+
"asset_cfg": SceneEntityCfg("robot", body_names="base"),
193+
"com_range": {"x": (-0.05, 0.05), "y": (-0.05, 0.05), "z": (-0.01, 0.01)},
194+
},
195+
),
196+
newton=None,
197+
)
198+
164199
# reset
165200
base_external_force_torque = EventTerm(
166201
func=mdp.apply_external_force_torque,
@@ -206,41 +241,6 @@ class EventsCfg:
206241
)
207242

208243

209-
@configclass
210-
class StartupEventsCfg:
211-
# startup
212-
physics_material = EventTerm(
213-
func=mdp.randomize_rigid_body_material,
214-
mode="startup",
215-
params={
216-
"asset_cfg": SceneEntityCfg("robot", body_names=".*"),
217-
"static_friction_range": (0.8, 0.8),
218-
"dynamic_friction_range": (0.6, 0.6),
219-
"restitution_range": (0.0, 0.0),
220-
"num_buckets": 64,
221-
},
222-
)
223-
224-
add_base_mass = EventTerm(
225-
func=mdp.randomize_rigid_body_mass,
226-
mode="startup",
227-
params={
228-
"asset_cfg": SceneEntityCfg("robot", body_names="base"),
229-
"mass_distribution_params": (-5.0, 5.0),
230-
"operation": "add",
231-
},
232-
)
233-
234-
base_com = EventTerm(
235-
func=mdp.randomize_rigid_body_com,
236-
mode="startup",
237-
params={
238-
"asset_cfg": SceneEntityCfg("robot", body_names="base"),
239-
"com_range": {"x": (-0.05, 0.05), "y": (-0.05, 0.05), "z": (-0.01, 0.01)},
240-
},
241-
)
242-
243-
244244
@configclass
245245
class RewardsCfg:
246246
"""Reward terms for the MDP."""
@@ -286,6 +286,10 @@ class TerminationsCfg:
286286
func=mdp.illegal_contact,
287287
params={"sensor_cfg": SceneEntityCfg("contact_forces", body_names="base"), "threshold": 1.0},
288288
)
289+
body_lin_vel = DoneTerm(
290+
func=mdp.body_lin_vel_out_of_limit,
291+
params={"max_velocity": 20.0, "asset_cfg": SceneEntityCfg("robot", body_names=".*")},
292+
)
289293

290294

291295
@configclass
@@ -313,7 +317,7 @@ class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg):
313317
# MDP settings
314318
rewards: RewardsCfg = RewardsCfg()
315319
terminations: TerminationsCfg = TerminationsCfg()
316-
events: EventsCfg = MISSING
320+
events: EventsCfg = EventsCfg()
317321
curriculum: CurriculumCfg = CurriculumCfg()
318322

319323
def __post_init__(self):

0 commit comments

Comments
 (0)