Skip to content

Commit 6d69d71

Browse files
friction randomization
1 parent 3919256 commit 6d69d71

File tree

2 files changed

+373
-2
lines changed

2 files changed

+373
-2
lines changed

source/isaaclab/isaaclab/envs/mdp/events.py

Lines changed: 89 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,55 @@ def randomize_rigid_body_scale(
4343

4444
class randomize_rigid_body_material(ManagerTermBase):
4545
def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv):
46-
raise NotImplementedError("Not implemented")
46+
"""Initialize the term.
47+
48+
Args:
49+
cfg: The configuration of the event term.
50+
env: The environment instance.
51+
52+
Raises:
53+
ValueError: If the asset is not an Articulation.
54+
"""
55+
super().__init__(cfg, env)
56+
57+
# extract the used quantities (to enable type-hinting)
58+
self.asset_cfg: SceneEntityCfg = cfg.params["asset_cfg"]
59+
self.asset: Articulation = env.scene[self.asset_cfg.name]
60+
61+
if not isinstance(self.asset, (Articulation)):
62+
raise ValueError(
63+
f"Randomization term 'randomize_rigid_body_material' not supported for asset: '{self.asset_cfg.name}'"
64+
f" with type: '{type(self.asset)}'."
65+
)
66+
67+
# obtain number of shapes per body (needed for indexing the material properties correctly)
68+
# note: this is a workaround since the Articulation does not provide a direct way to obtain the number of shapes
69+
# per body. We use the physics simulation view to obtain the number of shapes per body.
70+
self.num_shapes_per_body = None
71+
if isinstance(self.asset, Articulation) and self.asset_cfg.body_ids != slice(None):
72+
self.num_shapes_per_body = []
73+
for shapes in self.asset.root_newton_view.body_shapes:
74+
self.num_shapes_per_body.append(len(shapes))
75+
76+
# obtain parameters for sampling friction and restitution values
77+
static_friction_range = cfg.params.get("static_friction_range", (1.0, 1.0))
78+
dynamic_friction_range = cfg.params.get("dynamic_friction_range", (1.0, 1.0))
79+
restitution_range = cfg.params.get("restitution_range", (0.0, 0.0))
80+
num_buckets = int(cfg.params.get("num_buckets", 1))
81+
82+
# sample material properties from the given ranges
83+
# note: we only sample the materials once during initialization
84+
# afterwards these are randomly assigned to the geometries of the asset
85+
range_list = [static_friction_range, dynamic_friction_range, restitution_range]
86+
ranges = torch.tensor(range_list, device=self.asset.device)
87+
self.material_buckets = math_utils.sample_uniform(
88+
ranges[:, 0], ranges[:, 1], (num_buckets, 3), device=self.asset.device
89+
)
90+
91+
# ensure dynamic friction is always less than static friction
92+
make_consistent = cfg.params.get("make_consistent", False)
93+
if make_consistent:
94+
self.material_buckets[:, 1] = torch.min(self.material_buckets[:, 0], self.material_buckets[:, 1])
4795

4896
def __call__(
4997
self,
@@ -56,7 +104,46 @@ def __call__(
56104
asset_cfg: SceneEntityCfg,
57105
make_consistent: bool = False,
58106
):
59-
raise NotImplementedError("Not implemented")
107+
108+
# resolve environment ids
109+
if env_ids is None:
110+
env_ids = torch.arange(env.scene.num_envs, device="cpu")
111+
else:
112+
env_ids = env_ids.cpu()
113+
# retrieve material buffer from the physics simulation
114+
# materials = self.asset.root_physx_view.get_material_properties()
115+
material_mu = wp.to_torch(
116+
self.asset.root_newton_view.get_attribute("shape_material_mu", self.asset.root_newton_model)
117+
).clone()
118+
# randomly assign material IDs to the geometries
119+
total_num_shapes = material_mu.shape[1]
120+
bucket_ids = torch.randint(0, num_buckets, (len(env_ids), total_num_shapes), device=self.asset.device)
121+
material_samples = self.material_buckets[bucket_ids]
122+
# print("material_mu before update:\n", material_mu.shape, material_mu)
123+
# update material buffer with new samples
124+
if self.num_shapes_per_body is not None:
125+
# sample material properties from the given ranges
126+
for body_id in self.asset_cfg.body_ids:
127+
# obtain indices of shapes for the body
128+
start_idx = sum(self.num_shapes_per_body[:body_id])
129+
end_idx = start_idx + self.num_shapes_per_body[body_id]
130+
# assign the new materials
131+
# material samples are of shape: num_env_ids x total_num_shapes x 3
132+
material_mu[env_ids, start_idx:end_idx] = material_samples[:, start_idx:end_idx, 0]
133+
else:
134+
# assign all the materials
135+
material_mu[env_ids, :] = material_samples[:, :, 0]
136+
137+
# apply to simulation
138+
mask = torch.zeros((env.scene.num_envs,), dtype=torch.bool, device=env.device)
139+
mask[env_ids] = True
140+
self.asset.root_newton_view.set_attribute(
141+
"shape_material_mu", self.asset.root_newton_model, wp.from_torch(material_mu), mask=mask
142+
)
143+
NewtonManager._solver.notify_model_changed(SolverNotifyFlags.SHAPE_PROPERTIES)
144+
145+
# material_mu = wp.to_torch(self.asset.root_newton_view.get_attribute("shape_material_mu", self.asset.root_newton_model)).clone()
146+
# print("material_mu after update:\n", material_mu.shape, material_mu)
60147

61148

62149
def randomize_rigid_body_mass(
Lines changed: 284 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,284 @@
1+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2+
# All rights reserved.
3+
#
4+
# SPDX-License-Identifier: BSD-3-Clause
5+
6+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
7+
# All rights reserved.
8+
#
9+
# SPDX-License-Identifier: BSD-3-Clause
10+
11+
"""
12+
This script demonstrates the environment concept that combines a scene with an action,
13+
observation and event manager for a quadruped robot.
14+
15+
A locomotion policy is loaded and used to control the robot. This shows how to use the
16+
environment with a policy.
17+
"""
18+
19+
"""Launch Isaac Sim Simulator first."""
20+
21+
22+
from isaaclab.app import AppLauncher
23+
24+
simulation_app = AppLauncher(headless=True).app
25+
26+
"""Rest everything follows."""
27+
28+
import numpy as np
29+
import torch
30+
31+
import omni.usd
32+
import pytest
33+
34+
import isaaclab.envs.mdp as mdp
35+
import isaaclab.sim as sim_utils
36+
from isaaclab.assets import ArticulationCfg, AssetBaseCfg
37+
from isaaclab.envs import ManagerBasedEnv, ManagerBasedEnvCfg
38+
from isaaclab.managers import EventTermCfg as EventTerm
39+
from isaaclab.managers import ObservationGroupCfg as ObsGroup
40+
from isaaclab.managers import ObservationTermCfg as ObsTerm
41+
from isaaclab.managers import SceneEntityCfg
42+
from isaaclab.scene import InteractiveSceneCfg
43+
from isaaclab.sim._impl.newton_manager import NewtonManager
44+
from isaaclab.terrains import TerrainImporterCfg
45+
from isaaclab.utils import configclass
46+
from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR, NVIDIA_NUCLEUS_DIR
47+
48+
##
49+
# Pre-defined configs
50+
##
51+
from isaaclab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort: skip
52+
from isaaclab_assets import ANYMAL_D_CFG # isort: skip
53+
54+
55+
##
56+
# Scene definition
57+
##
58+
@configclass
59+
class MySceneCfg(InteractiveSceneCfg):
60+
"""Example scene configuration."""
61+
62+
# add terrain
63+
terrain = TerrainImporterCfg(
64+
prim_path="/World/ground",
65+
terrain_type="plane",
66+
terrain_generator=ROUGH_TERRAINS_CFG,
67+
physics_material=sim_utils.RigidBodyMaterialCfg(
68+
friction_combine_mode="multiply",
69+
restitution_combine_mode="multiply",
70+
static_friction=1.0,
71+
dynamic_friction=1.0,
72+
),
73+
visual_material=sim_utils.MdlFileCfg(
74+
mdl_path=f"{ISAACLAB_NUCLEUS_DIR}/Materials/TilesMarbleSpiderWhiteBrickBondHoned/TilesMarbleSpiderWhiteBrickBondHoned.mdl",
75+
project_uvw=True,
76+
texture_scale=(0.25, 0.25),
77+
),
78+
debug_vis=False,
79+
)
80+
81+
# add robot
82+
robot: ArticulationCfg = ANYMAL_D_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
83+
84+
# lights
85+
sky_light = AssetBaseCfg(
86+
prim_path="/World/skyLight",
87+
spawn=sim_utils.DomeLightCfg(
88+
intensity=900.0,
89+
texture_file=f"{NVIDIA_NUCLEUS_DIR}/Assets/Skies/Cloudy/kloofendal_48d_partly_cloudy_4k.hdr",
90+
visible_in_primary_ray=False,
91+
),
92+
)
93+
94+
95+
##
96+
# MDP settings
97+
##
98+
def constant_commands(env: ManagerBasedEnv) -> torch.Tensor:
99+
"""The generated command from the command generator."""
100+
return torch.tensor([[1, 0, 0]], device=env.device).repeat(env.num_envs, 1)
101+
102+
103+
@configclass
104+
class ActionsCfg:
105+
"""Action specifications for the MDP."""
106+
107+
joint_pos = mdp.JointPositionActionCfg(asset_name="robot", joint_names=[".*"], scale=0.5, use_default_offset=True)
108+
109+
110+
@configclass
111+
class ObservationsCfg:
112+
"""Observation specifications for the MDP."""
113+
114+
@configclass
115+
class PolicyCfg(ObsGroup):
116+
"""Observations for policy group."""
117+
118+
# observation terms (order preserved)
119+
base_pos_z = ObsTerm(
120+
func=mdp.base_pos_z,
121+
)
122+
123+
def __post_init__(self):
124+
self.enable_corruption = True
125+
self.concatenate_terms = True
126+
127+
# observation groups
128+
policy: PolicyCfg = PolicyCfg()
129+
130+
131+
@configclass
132+
class EventCfg:
133+
"""Configuration for events."""
134+
135+
pass
136+
137+
138+
@configclass
139+
class RandomizedEventCfg:
140+
"""Configuration for events."""
141+
142+
physics_material = EventTerm(
143+
func=mdp.randomize_rigid_body_material,
144+
mode="startup",
145+
params={
146+
"asset_cfg": SceneEntityCfg("robot", body_names=".*"),
147+
"static_friction_range": (0.3, 1.0),
148+
"dynamic_friction_range": (0.5, 0.5),
149+
"restitution_range": (0.0, 0.0),
150+
"num_buckets": 512,
151+
},
152+
)
153+
add_base_mass = EventTerm(
154+
func=mdp.randomize_rigid_body_mass,
155+
mode="startup",
156+
params={
157+
"asset_cfg": SceneEntityCfg("robot", body_names="base"),
158+
"mass_distribution_params": (-5.0, 5.0),
159+
"operation": "add",
160+
},
161+
)
162+
163+
164+
##
165+
# Environment configuration
166+
##
167+
@configclass
168+
class QuadrupedEnvCfg(ManagerBasedEnvCfg):
169+
randomize: bool = False
170+
device: str = "cuda:0"
171+
"""Configuration for the locomotion velocity-tracking environment."""
172+
# Scene settings
173+
scene: MySceneCfg = MySceneCfg(num_envs=3, env_spacing=2.5, replicate_physics=True)
174+
# Basic settings
175+
observations: ObservationsCfg = ObservationsCfg()
176+
actions: ActionsCfg = ActionsCfg()
177+
events: EventCfg | None = None
178+
179+
def __post_init__(self):
180+
"""Post initialization."""
181+
super().__post_init__()
182+
self.events = RandomizedEventCfg() if self.randomize else EventCfg()
183+
# general settings
184+
self.decimation = 4
185+
self.episode_length_s = 20.0
186+
# simulation settings
187+
self.sim.dt = 0.005
188+
self.sim.device = self.device
189+
190+
191+
@pytest.mark.parametrize("device", ["cuda:0"])
192+
def test_randomized_mass(device):
193+
omni.usd.get_context().new_stage()
194+
env = ManagerBasedEnv(cfg=QuadrupedEnvCfg(randomize=True, device=device))
195+
obs, _ = env.reset()
196+
actions = torch.rand((3, 12), device=env.device) # 12 joints in ANMAL-D
197+
# reset
198+
for i in range(10):
199+
obs, _ = env.step(actions)
200+
# reset counters
201+
masses = NewtonManager._model.body_mass.numpy()
202+
masses_mjwarp = NewtonManager._solver.mjw_model.body_mass.numpy()
203+
masses = masses.reshape((3, -1))
204+
masses_mjwarp = masses_mjwarp.reshape((3, -1))
205+
# print("[INFO]: Environment reset. Observations:\n", obs)
206+
# 1 index is for body base in mjwarp
207+
# 0 index is for body base in newton
208+
assert (np.abs(masses[0, 0] - masses[1, 0]) > 0.0).all()
209+
assert (np.abs(masses[1, 0] - masses[2, 0]) > 0.0).all()
210+
assert (np.abs(masses_mjwarp[0, 1] - masses_mjwarp[1, 1]) > 0.0).all()
211+
assert (np.abs(masses_mjwarp[1, 1] - masses_mjwarp[2, 1]) > 0.0).all()
212+
# environment should have different heights
213+
heights = obs["policy"].cpu().numpy()
214+
assert np.abs(heights[0] - heights[1]) > 0.0
215+
assert np.abs(heights[1] - heights[2]) > 0.0
216+
env.close()
217+
218+
219+
@pytest.mark.parametrize("device", ["cuda:0"])
220+
def test_constant_mass(device):
221+
omni.usd.get_context().new_stage()
222+
env = ManagerBasedEnv(cfg=QuadrupedEnvCfg(randomize=False, device=device))
223+
obs, _ = env.reset()
224+
actions = torch.rand((3, 12), device=env.device) # 12 joints in ANMAL-D
225+
# reset
226+
for i in range(10):
227+
obs, _ = env.step(actions)
228+
masses = NewtonManager._model.body_mass.numpy()
229+
masses_mjwarp = NewtonManager._solver.mjw_model.body_mass.numpy()
230+
masses = masses.reshape((3, -1))
231+
masses_mjwarp = masses_mjwarp.reshape((3, -1))
232+
# print("[INFO]: Environment reset. Observations:\n", obs)
233+
assert (np.abs(masses[0, :] - masses[1, :]) == 0.0).all()
234+
assert (np.abs(masses[1, :] - masses[2, :]) == 0.0).all()
235+
assert (np.abs(masses_mjwarp[0, :] - masses_mjwarp[1, :]) == 0.0).all()
236+
assert (np.abs(masses_mjwarp[1, :] - masses_mjwarp[2, :]) == 0.0).all()
237+
# environment should have different heights
238+
# heights = obs["policy"].cpu().numpy()
239+
# assert(np.abs(heights[0]- heights[1]) < 1e-2)
240+
# assert(np.abs(heights[1]- heights[2]) < 1e-2)
241+
env.close()
242+
243+
244+
@pytest.mark.parametrize("device", ["cuda:0"])
245+
def test_randomized_material(device):
246+
omni.usd.get_context().new_stage()
247+
env = ManagerBasedEnv(cfg=QuadrupedEnvCfg(randomize=True, device=device))
248+
obs, _ = env.reset()
249+
actions = torch.rand((3, 12), device=env.device) # 12 joints in ANMAL-D
250+
# reset
251+
for i in range(10):
252+
obs, _ = env.step(actions)
253+
# reset counters
254+
# materials = NewtonManager._model.shape_material_mu.numpy()
255+
# to_newton_shape_index = NewtonManager._solver.model.to_newton_shape_index.numpy()
256+
materials_mjwarp = NewtonManager._solver.mjw_model.geom_friction.numpy()
257+
ngeom = NewtonManager._solver.mjw_model.ngeom
258+
materials_mjwarp = materials_mjwarp[:, :, 0]
259+
# newton_shape_index = to_newton_shape_index[:, :ngeom]
260+
materials_mjwarp = materials_mjwarp.reshape(3, ngeom)
261+
# materials_newton = materials[to_newton_shape_index]
262+
print("materials_mjwarp:\n", materials_mjwarp)
263+
# there is a non-zero chance that the same material gets assigned to the same body since this is a random process
264+
assert (np.abs(materials_mjwarp[0, 2:] - materials_mjwarp[1, 2:]) > 0.0).all()
265+
assert (np.abs(materials_mjwarp[1, 2:] - materials_mjwarp[2, 2:]) > 0.0).all()
266+
env.close()
267+
268+
269+
@pytest.mark.parametrize("device", ["cuda:0"])
270+
def test_constant_material(device):
271+
omni.usd.get_context().new_stage()
272+
env = ManagerBasedEnv(cfg=QuadrupedEnvCfg(randomize=False, device=device))
273+
obs, _ = env.reset()
274+
actions = torch.rand((3, 12), device=env.device) # 12 joints in ANMAL-D
275+
# reset
276+
for i in range(10):
277+
obs, _ = env.step(actions)
278+
# reset counters
279+
materials_mjwarp = NewtonManager._solver.mjw_model.geom_friction.numpy()
280+
ngeom = NewtonManager._solver.mjw_model.ngeom
281+
materials_mjwarp = materials_mjwarp[:, :, 0].reshape(3, ngeom)
282+
assert (np.abs(materials_mjwarp[0, :] - materials_mjwarp[1, :]) == 0.0).all()
283+
assert (np.abs(materials_mjwarp[1, :] - materials_mjwarp[2, :]) == 0.0).all()
284+
env.close()

0 commit comments

Comments
 (0)