Skip to content

Commit f4812b3

Browse files
committed
add more event for newton physx parity
1 parent 268b94f commit f4812b3

3 files changed

Lines changed: 163 additions & 54 deletions

File tree

source/isaaclab/docs/CHANGELOG.rst

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,13 @@ Changed
1515

1616
* Updated :class:`~isaaclab.envs.mdp.randomize_rigid_body_material` to use
1717
backend-specific APIs (PhysX 3-tuple vs Newton separate friction/restitution).
18+
* Converted :func:`~isaaclab.envs.mdp.randomize_rigid_body_collider_offsets` from a
19+
plain function to a :class:`~isaaclab.managers.ManagerTermBase` class with automatic
20+
backend detection. PhysX uses rest/contact offsets directly; Newton maps them to
21+
``shape_margin`` and ``shape_gap``.
22+
* Updated :func:`~isaaclab.envs.mdp.randomize_rigid_body_com` to detect the active
23+
physics backend and pass position-only (vec3) for Newton vs full pose (pos + quat)
24+
for PhysX.
1825

1926

2027
4.5.27 (2026-04-08)

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

Lines changed: 98 additions & 53 deletions
Original file line numberDiff line numberDiff line change
@@ -638,71 +638,116 @@ def randomize_rigid_body_com(
638638
ranges[:, 0], ranges[:, 1], (len(env_ids), 3), device=asset.device
639639
).unsqueeze(1)
640640

641-
# get the current com of the bodies (num_assets, num_bodies)
641+
# get the current com of the bodies (num_assets, num_bodies, 7)
642642
coms = wp.to_torch(asset.data.body_com_pose_b).clone()
643643

644-
# Randomize the com in range
644+
# Randomize the com position
645645
coms[env_ids[:, None], body_ids, :3] += rand_samples
646646

647-
# Set the new coms
648-
asset.set_coms_index(coms=coms, env_ids=env_ids)
649-
650-
651-
def randomize_rigid_body_collider_offsets(
652-
env: ManagerBasedEnv,
653-
env_ids: torch.Tensor | None,
654-
asset_cfg: SceneEntityCfg,
655-
rest_offset_distribution_params: tuple[float, float] | None = None,
656-
contact_offset_distribution_params: tuple[float, float] | None = None,
657-
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
658-
):
659-
"""Randomize the collider parameters of rigid bodies in an asset by adding, scaling, or setting random values.
647+
# Newton's set_coms_index expects position-only (vec3f), while PhysX expects
648+
# the full pose (pos + quat). Detect backend to pass the correct shape.
649+
manager_name = env.sim.physics_manager.__name__.lower()
650+
if "newton" in manager_name:
651+
asset.set_coms_index(coms=coms[..., :3], env_ids=env_ids)
652+
else:
653+
asset.set_coms_index(coms=coms, env_ids=env_ids)
660654

661-
This function allows randomizing the collider parameters of the asset, such as rest and contact offsets.
662-
These correspond to the physics engine collider properties that affect the collision checking.
663655

664-
The function samples random values from the given distribution parameters and applies the operation to
665-
the collider properties. It then sets the values into the physics simulation. If the distribution parameters
666-
are not provided for a particular property, the function does not modify the property.
656+
class randomize_rigid_body_collider_offsets(ManagerTermBase):
657+
"""Randomize the collider parameters of rigid bodies by setting random values.
667658
668-
Currently, the distribution parameters are applied as absolute values.
659+
Supports both PhysX (rest/contact offset) and Newton (shape_margin/shape_gap).
660+
For Newton, ``rest_offset`` maps to ``shape_margin`` and ``contact_offset`` is
661+
converted to ``shape_gap`` via ``gap = contact_offset - margin``.
669662
670663
.. tip::
671-
This function uses CPU tensors to assign the collision properties. It is recommended to use this function
672-
only during the initialization of the environment.
664+
It is recommended to use this function only during environment initialization.
673665
"""
674-
# extract the used quantities (to enable type-hinting)
675-
asset: RigidObject | Articulation = env.scene[asset_cfg.name]
676666

677-
# resolve environment ids
678-
if env_ids is None:
679-
env_ids = torch.arange(env.scene.num_envs, device="cpu")
667+
def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv):
668+
from isaaclab.assets import BaseArticulation, BaseRigidObject
680669

681-
# sample collider properties from the given ranges and set into the physics simulation
682-
# -- rest offsets
683-
if rest_offset_distribution_params is not None:
684-
rest_offset = wp.to_torch(asset.root_view.get_rest_offsets()).clone()
685-
rest_offset = _randomize_prop_by_op(
686-
rest_offset,
687-
rest_offset_distribution_params,
688-
None,
689-
slice(None),
690-
operation="abs",
691-
distribution=distribution,
692-
)
693-
asset.root_view.set_rest_offsets(rest_offset, env_ids.cpu())
694-
# -- contact offsets
695-
if contact_offset_distribution_params is not None:
696-
contact_offset = wp.to_torch(asset.root_view.get_contact_offsets()).clone()
697-
contact_offset = _randomize_prop_by_op(
698-
contact_offset,
699-
contact_offset_distribution_params,
700-
None,
701-
slice(None),
702-
operation="abs",
703-
distribution=distribution,
704-
)
705-
asset.root_view.set_contact_offsets(contact_offset, env_ids.cpu())
670+
super().__init__(cfg, env)
671+
672+
self.asset_cfg: SceneEntityCfg = cfg.params["asset_cfg"]
673+
self.asset: RigidObject | Articulation = env.scene[self.asset_cfg.name]
674+
675+
if not isinstance(self.asset, (BaseRigidObject, BaseArticulation)):
676+
raise ValueError(
677+
f"Randomization term 'randomize_rigid_body_collider_offsets' not supported for asset:"
678+
f" '{self.asset_cfg.name}' with type: '{type(self.asset)}'."
679+
)
680+
681+
if "newton" in env.sim.physics_manager.__name__.lower():
682+
self._init_newton()
683+
else:
684+
self._init_physx()
685+
686+
def _init_physx(self) -> None:
687+
asset = self.asset
688+
self._default_rest = wp.to_torch(asset.root_view.get_rest_offsets()).clone() # type: ignore[union-attr]
689+
self._default_contact = wp.to_torch(asset.root_view.get_contact_offsets()).clone() # type: ignore[union-attr]
690+
self._env_ids_device = "cpu"
691+
self._write_rest = lambda data, ids: asset.root_view.set_rest_offsets(data, ids) # type: ignore[union-attr]
692+
self._write_contact = lambda data, ids: asset.root_view.set_contact_offsets(data, ids) # type: ignore[union-attr]
693+
694+
def _init_newton(self) -> None:
695+
import isaaclab_newton.physics.newton_manager as nm
696+
from newton.solvers import SolverNotifyFlags
697+
698+
notify = lambda: nm.NewtonManager.add_model_change(SolverNotifyFlags.SHAPE_PROPERTIES) # noqa: E731
699+
700+
model = nm.NewtonManager.get_model()
701+
margin_buf = self.asset._root_view.get_attribute("shape_margin", model)[:, 0] # type: ignore[union-attr]
702+
gap_buf = self.asset._root_view.get_attribute("shape_gap", model)[:, 0] # type: ignore[union-attr]
703+
704+
self._default_rest = wp.to_torch(margin_buf).clone()
705+
self._default_contact = wp.to_torch(gap_buf).clone()
706+
self._env_ids_device = self._default_rest.device
707+
margin_view = wp.to_torch(margin_buf)
708+
gap_view = wp.to_torch(gap_buf)
709+
710+
def _write_margin(data: torch.Tensor, ids: torch.Tensor) -> None:
711+
self._default_rest[ids] = data[ids]
712+
margin_view[ids] = data[ids]
713+
notify()
714+
715+
def _write_gap(data: torch.Tensor, ids: torch.Tensor) -> None:
716+
gap = torch.clamp(data - self._default_rest, min=0.0)
717+
self._default_contact[ids] = gap[ids]
718+
gap_view[ids] = gap[ids]
719+
notify()
720+
721+
self._write_rest = _write_margin
722+
self._write_contact = _write_gap
723+
724+
def __call__(
725+
self,
726+
env: ManagerBasedEnv,
727+
env_ids: torch.Tensor | None,
728+
asset_cfg: SceneEntityCfg,
729+
rest_offset_distribution_params: tuple[float, float] | None = None,
730+
contact_offset_distribution_params: tuple[float, float] | None = None,
731+
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
732+
):
733+
if env_ids is None:
734+
env_ids = torch.arange(env.scene.num_envs, device=self._env_ids_device)
735+
else:
736+
env_ids = env_ids.to(self._env_ids_device)
737+
738+
if rest_offset_distribution_params is not None:
739+
data = _randomize_prop_by_op(
740+
self._default_rest.clone(), rest_offset_distribution_params,
741+
None, slice(None), operation="abs", distribution=distribution,
742+
)
743+
self._write_rest(data, env_ids)
744+
745+
if contact_offset_distribution_params is not None:
746+
data = _randomize_prop_by_op(
747+
self._default_contact.clone(), contact_offset_distribution_params,
748+
None, slice(None), operation="abs", distribution=distribution,
749+
)
750+
self._write_contact(data, env_ids)
706751

707752

708753
class randomize_physics_scene_gravity(ManagerTermBase):

source/isaaclab_newton/test/assets/test_articulation.py

Lines changed: 58 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2486,7 +2486,6 @@ def _patched_simulate(cls):
24862486
f"body_q was stale when collide() ran: diff={diff:.4f}m, jq={jq_root.tolist()}, bq={bq_root.tolist()}"
24872487
)
24882488

2489-
24902489
@pytest.mark.parametrize("add_ground_plane", [True])
24912490
@pytest.mark.parametrize("num_articulations", [1, 2])
24922491
@pytest.mark.parametrize("device", ["cuda:0", "cpu"])
@@ -2544,6 +2543,64 @@ def test_set_material_properties(sim, num_articulations, device, add_ground_plan
25442543
torch.testing.assert_close(mu_updated[:, 0:1], subset_friction)
25452544
torch.testing.assert_close(restitution_updated[:, 0:1], subset_restitution)
25462545

2546+
@pytest.mark.parametrize("num_articulations", [2])
2547+
@pytest.mark.parametrize("device", ["cuda:0"])
2548+
@pytest.mark.parametrize("add_ground_plane", [True])
2549+
@pytest.mark.parametrize("articulation_type", ["anymal"])
2550+
@pytest.mark.isaacsim_ci
2551+
def test_randomize_rigid_body_com(sim, num_articulations, device, add_ground_plane, articulation_type):
2552+
"""Test that randomize_rigid_body_com modifies CoM and affects simulation dynamics."""
2553+
articulation_cfg = generate_articulation_cfg(articulation_type=articulation_type)
2554+
articulation, _ = generate_articulation(articulation_cfg, num_articulations, device=device)
2555+
2556+
sim.reset()
2557+
assert articulation.is_initialized
2558+
2559+
original_com = wp.to_torch(articulation.data.body_com_pos_b).clone()
2560+
2561+
com_offset = torch.zeros(num_articulations, articulation.num_bodies, 3, device=device)
2562+
com_offset[..., 0] = 0.5
2563+
new_com = original_com + com_offset
2564+
env_ids = torch.arange(num_articulations, device=device, dtype=torch.int32)
2565+
articulation.set_coms_index(coms=new_com, env_ids=env_ids)
2566+
2567+
updated_com = wp.to_torch(articulation.data.body_com_pos_b)
2568+
torch.testing.assert_close(updated_com, new_com, atol=1e-5, rtol=1e-5)
2569+
2570+
2571+
@pytest.mark.parametrize("num_articulations", [2])
2572+
@pytest.mark.parametrize("device", ["cuda:0"])
2573+
@pytest.mark.parametrize("add_ground_plane", [True])
2574+
@pytest.mark.parametrize("articulation_type", ["anymal"])
2575+
@pytest.mark.isaacsim_ci
2576+
def test_randomize_rigid_body_collider_offsets(sim, num_articulations, device, add_ground_plane, articulation_type):
2577+
"""Test that Newton collider offset randomization (shape_margin, shape_gap) takes effect."""
2578+
articulation_cfg = generate_articulation_cfg(articulation_type=articulation_type)
2579+
articulation, _ = generate_articulation(articulation_cfg, num_articulations, device=device)
2580+
2581+
sim.reset()
2582+
assert articulation.is_initialized
2583+
2584+
model = SimulationManager.get_model()
2585+
original_margin = wp.to_torch(articulation.root_view.get_attribute("shape_margin", model)).clone()
2586+
original_gap = wp.to_torch(articulation.root_view.get_attribute("shape_gap", model)).clone()
2587+
2588+
new_margin = original_margin.clone()
2589+
new_margin[:, 0] += 0.01
2590+
articulation.root_view.set_attribute("shape_margin", model, wp.from_torch(new_margin, dtype=wp.float32))
2591+
2592+
new_gap = original_gap.clone()
2593+
new_gap[:, 0] += 0.005
2594+
articulation.root_view.set_attribute("shape_gap", model, wp.from_torch(new_gap, dtype=wp.float32))
2595+
2596+
with wp.ScopedDevice(device):
2597+
SimulationManager._solver.notify_model_changed(SolverNotifyFlags.SHAPE_PROPERTIES)
2598+
2599+
updated_margin = wp.to_torch(articulation.root_view.get_attribute("shape_margin", model))
2600+
updated_gap = wp.to_torch(articulation.root_view.get_attribute("shape_gap", model))
2601+
torch.testing.assert_close(updated_margin, new_margin)
2602+
torch.testing.assert_close(updated_gap, new_gap)
2603+
25472604

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

0 commit comments

Comments
 (0)