Skip to content
2 changes: 1 addition & 1 deletion source/isaaclab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "4.5.30"
version = "4.5.31"

# Description
title = "Isaac Lab framework for Robot Learning"
Expand Down
27 changes: 27 additions & 0 deletions source/isaaclab/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,33 @@
Changelog
---------

4.5.31 (2026-04-13)
~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added :class:`~isaaclab.envs.mdp.randomize_rigid_body_inertia` event term for
randomizing body inertia tensors independently of mass. Supports diagonal-only
(Ixx, Iyy, Izz) and full 3x3 modes.

Changed
^^^^^^^

* Split :class:`~isaaclab.envs.mdp.randomize_rigid_body_material` into
backend-specific implementations. PhysX uses bucket-based 3-tuple materials via the
tensor API; Newton samples friction and restitution continuously per shape via
view-level attribute bindings.
* Converted ``randomize_rigid_body_com`` from a plain function to a
:class:`~isaaclab.managers.ManagerTermBase` class with repeatable randomization
from cached defaults. Newton passes position-only (vec3); PhysX passes full pose
(pos + quat).
* Converted ``randomize_rigid_body_collider_offsets`` from a plain function to a
:class:`~isaaclab.managers.ManagerTermBase` class with backend-specific
implementations. PhysX uses rest/contact offsets directly; Newton maps them to
``shape_margin`` and ``shape_gap``.


4.5.30 (2026-04-13)
~~~~~~~~~~~~~~~~~~~

Expand Down
2 changes: 2 additions & 0 deletions source/isaaclab/isaaclab/envs/mdp/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ __all__ = [
"randomize_physics_scene_gravity",
"randomize_rigid_body_collider_offsets",
"randomize_rigid_body_com",
"randomize_rigid_body_inertia",
"randomize_rigid_body_mass",
"randomize_rigid_body_material",
"randomize_rigid_body_scale",
Expand Down Expand Up @@ -195,6 +196,7 @@ from .events import (
randomize_physics_scene_gravity,
randomize_rigid_body_collider_offsets,
randomize_rigid_body_com,
randomize_rigid_body_inertia,
randomize_rigid_body_mass,
randomize_rigid_body_material,
randomize_rigid_body_scale,
Expand Down
781 changes: 620 additions & 161 deletions source/isaaclab/isaaclab/envs/mdp/events.py

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion source/isaaclab_newton/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.5.11"
version = "0.5.12"

# Description
title = "Newton simulation interfaces for IsaacLab core package"
Expand Down
11 changes: 11 additions & 0 deletions source/isaaclab_newton/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,16 @@
Changelog
---------

0.5.12 (2026-04-13)
~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added ``set_friction_index/mask`` and ``set_restitution_index/mask`` methods to
Newton assets for native material property randomization.


0.5.11 (2026-04-13)
~~~~~~~~~~~~~~~~~~~

Expand All @@ -12,6 +22,7 @@ Added
registration, wildcard body matching, and zero-copy transform views.



0.5.10 (2026-04-05)
~~~~~~~~~~~~~~~~~~~

Expand Down
117 changes: 117 additions & 0 deletions source/isaaclab_newton/test/assets/test_articulation.py
Comment thread
AntoineRichard marked this conversation as resolved.
Original file line number Diff line number Diff line change
Expand Up @@ -2487,5 +2487,122 @@ def _patched_simulate(cls):
)


@pytest.mark.parametrize("add_ground_plane", [True])
@pytest.mark.parametrize("num_articulations", [1, 2])
@pytest.mark.parametrize("device", ["cuda:0", "cpu"])
@pytest.mark.parametrize("articulation_type", ["panda"])
@pytest.mark.isaacsim_ci
def test_set_material_properties(sim, num_articulations, device, add_ground_plane, articulation_type):
"""Test getting and setting material properties (friction/restitution) via view-level APIs."""
articulation_cfg = generate_articulation_cfg(articulation_type=articulation_type)
articulation, _ = generate_articulation(
articulation_cfg=articulation_cfg, num_articulations=num_articulations, device=device
)

# Play the simulator
sim.reset()

# Get friction/restitution bindings via view-level API
model = SimulationManager.get_model()
friction_binding = articulation._root_view.get_attribute("shape_material_mu", model)[:, 0]
restitution_binding = articulation._root_view.get_attribute("shape_material_restitution", model)[:, 0]
num_shapes = friction_binding.shape[1]

# Test 1: Set all shapes via in-place writes to the warp binding
friction = torch.empty(num_articulations, num_shapes, device=device).uniform_(0.4, 0.8)
restitution = torch.empty(num_articulations, num_shapes, device=device).uniform_(0.0, 0.2)

wp.to_torch(friction_binding)[:] = friction
wp.to_torch(restitution_binding)[:] = restitution
SimulationManager.add_model_change(SolverNotifyFlags.SHAPE_PROPERTIES)

# Simulate physics
sim.step()
articulation.update(sim.cfg.dt)

# Verify by reading back from the binding
mu = wp.to_torch(friction_binding)
restitution_check = wp.to_torch(restitution_binding)
torch.testing.assert_close(mu, friction)
torch.testing.assert_close(restitution_check, restitution)

# Test 2: Set subset of shapes (only shape 0)
if num_shapes > 1:
subset_friction = torch.empty(num_articulations, device=device).uniform_(0.1, 0.2)
subset_restitution = torch.empty(num_articulations, device=device).uniform_(0.5, 0.6)

wp.to_torch(friction_binding)[:, 0] = subset_friction
wp.to_torch(restitution_binding)[:, 0] = subset_restitution
SimulationManager.add_model_change(SolverNotifyFlags.SHAPE_PROPERTIES)

sim.step()
articulation.update(sim.cfg.dt)

# Check only the subset was updated
mu_updated = wp.to_torch(friction_binding)
restitution_updated = wp.to_torch(restitution_binding)
torch.testing.assert_close(mu_updated[:, 0], subset_friction)
torch.testing.assert_close(restitution_updated[:, 0], subset_restitution)


@pytest.mark.parametrize("num_articulations", [2])
@pytest.mark.parametrize("device", ["cuda:0"])
@pytest.mark.parametrize("add_ground_plane", [True])
@pytest.mark.parametrize("articulation_type", ["anymal"])
@pytest.mark.isaacsim_ci
def test_randomize_rigid_body_com(sim, num_articulations, device, add_ground_plane, articulation_type):
"""Test that randomize_rigid_body_com modifies CoM and affects simulation dynamics."""
articulation_cfg = generate_articulation_cfg(articulation_type=articulation_type)
articulation, _ = generate_articulation(articulation_cfg, num_articulations, device=device)

sim.reset()
assert articulation.is_initialized

original_com = wp.to_torch(articulation.data.body_com_pos_b).clone()

com_offset = torch.zeros(num_articulations, articulation.num_bodies, 3, device=device)
com_offset[..., 0] = 0.5
new_com = original_com + com_offset
env_ids = torch.arange(num_articulations, device=device, dtype=torch.int32)
articulation.set_coms_index(coms=new_com, env_ids=env_ids)

updated_com = wp.to_torch(articulation.data.body_com_pos_b)
torch.testing.assert_close(updated_com, new_com, atol=1e-5, rtol=1e-5)


@pytest.mark.parametrize("num_articulations", [2])
@pytest.mark.parametrize("device", ["cuda:0"])
@pytest.mark.parametrize("add_ground_plane", [True])
@pytest.mark.parametrize("articulation_type", ["anymal"])
@pytest.mark.isaacsim_ci
def test_randomize_rigid_body_collider_offsets(sim, num_articulations, device, add_ground_plane, articulation_type):
"""Test that Newton collider offset randomization (shape_margin, shape_gap) takes effect."""
articulation_cfg = generate_articulation_cfg(articulation_type=articulation_type)
articulation, _ = generate_articulation(articulation_cfg, num_articulations, device=device)

sim.reset()
assert articulation.is_initialized

model = SimulationManager.get_model()
original_margin = wp.to_torch(articulation.root_view.get_attribute("shape_margin", model)).clone()
original_gap = wp.to_torch(articulation.root_view.get_attribute("shape_gap", model)).clone()

new_margin = original_margin.clone()
new_margin[:, 0] += 0.01
articulation.root_view.set_attribute("shape_margin", model, wp.from_torch(new_margin, dtype=wp.float32))

new_gap = original_gap.clone()
new_gap[:, 0] += 0.005
articulation.root_view.set_attribute("shape_gap", model, wp.from_torch(new_gap, dtype=wp.float32))

with wp.ScopedDevice(device):
SimulationManager._solver.notify_model_changed(SolverNotifyFlags.SHAPE_PROPERTIES)

updated_margin = wp.to_torch(articulation.root_view.get_attribute("shape_margin", model))
updated_gap = wp.to_torch(articulation.root_view.get_attribute("shape_gap", model))
torch.testing.assert_close(updated_margin, new_margin)
torch.testing.assert_close(updated_gap, new_gap)


if __name__ == "__main__":
pytest.main([__file__, "-v", "--maxfail=1"])
Loading
Loading