Skip to content

Commit e5b1aaa

Browse files
GiulioRomualdijtigue-bdaiMayankm96
authored andcommitted
Randomizes viscous and dynamic joint friction based on IsaacSim 5.0 (#3318)
<!-- Thank you for your interest in sending a pull request. Please make sure to check the contribution guidelines. Link: https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html --> This PR fixes #3266, adding the possibility to randomize the friction coefficient when isaacsim is higher than 5.0.0 <!-- As a practice, it is recommended to open an issue to have discussions on the proposed pull request. This makes it easier for the community to keep track of what is being developed or added, and if a given feature is demanded by more than one party. --> <!-- As you go through the list, delete the ones that are not applicable. --> - New feature (non-breaking change which adds functionality) Not applicable <!-- Example: | Before | After | | ------ | ----- | | _gif/png before_ | _gif/png after_ | To upload images to a PR -- simply drag and drop an image while in edit mode and it should upload the image directly. You can then paste that source into the above before/after sections. --> - [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with `./isaaclab.sh --format` - [x] I have made corresponding changes to the documentation - [x] My changes generate no new warnings - [x] I have added tests that prove my fix is effective or that my feature works - [x] I have updated the changelog and the corresponding version in the extension's `config/extension.toml` file - [x] I have added my name to the `CONTRIBUTORS.md` or my name already exists there <!-- As you go through the checklist above, you can mark something as done by putting an x character in it For example, - [x] I have done this task - [ ] I have not done this task --> --------- Signed-off-by: Giulio Romualdi <[email protected]> Signed-off-by: Mayank Mittal <[email protected]> Co-authored-by: James Tigue <[email protected]> Co-authored-by: Mayank Mittal <[email protected]>
1 parent 22b6591 commit e5b1aaa

File tree

5 files changed

+182
-20
lines changed

5 files changed

+182
-20
lines changed

source/isaaclab/config/extension.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
[package]
22

33
# Note: Semantic Versioning is used: https://semver.org/
4-
version = "0.46.2"
4+
version = "0.46.4"
55

66
# Description
77
title = "Isaac Lab framework for Robot Learning"

source/isaaclab/docs/CHANGELOG.rst

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,33 @@
11
Changelog
22
---------
33

4+
0.46.4 (2025-09-30)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Added
8+
^^^^^
9+
10+
* Added argument :attr:`traverse_instance_prims` to :meth:`~isaaclab.sim.utils.get_all_matching_child_prims` and
11+
:meth:`~isaaclab.sim.utils.get_first_matching_child_prim` to control whether to traverse instance prims
12+
during the traversal. Earlier, instanced prims were skipped since :meth:`Usd.Prim.GetChildren` did not return
13+
instanced prims, which is now fixed.
14+
15+
Changed
16+
^^^^^^^
17+
18+
* Made parsing of instanced prims in :meth:`~isaaclab.sim.utils.get_all_matching_child_prims` and
19+
:meth:`~isaaclab.sim.utils.get_first_matching_child_prim` as the default behavior.
20+
* Added parsing of instanced prims in :meth:`~isaaclab.sim.utils.make_uninstanceable` to make all prims uninstanceable.
21+
22+
23+
0.46.3 (2025-09-17)
24+
~~~~~~~~~~~~~~~~~~~
25+
26+
Added
27+
^^^^^
28+
29+
* Modified setter to support for viscous and dynamic joint friction coefficients in articulation based on IsaacSim 5.0.
30+
* Added randomization of viscous and dynamic joint friction coefficients in event term.
431

532
0.46.2 (2025-09-13)
633
~~~~~~~~~~~~~~~~~~~

source/isaaclab/isaaclab/assets/articulation/articulation.py

Lines changed: 46 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -827,24 +827,33 @@ def write_joint_armature_to_sim(
827827
def write_joint_friction_coefficient_to_sim(
828828
self,
829829
joint_friction_coeff: torch.Tensor | float,
830+
joint_dynamic_friction_coeff: torch.Tensor | float | None = None,
831+
joint_viscous_friction_coeff: torch.Tensor | float | None = None,
830832
joint_ids: Sequence[int] | slice | None = None,
831833
env_ids: Sequence[int] | None = None,
832834
):
833-
r"""Write joint static friction coefficients into the simulation.
835+
r"""Write joint friction coefficients into the simulation.
834836
835-
The joint static friction is a unitless quantity. It relates the magnitude of the spatial force transmitted
836-
from the parent body to the child body to the maximal static friction force that may be applied by the solver
837-
to resist the joint motion.
837+
For Isaac Sim versions below 5.0, only the static friction coefficient is set.
838+
This limits the resisting force or torque up to a maximum proportional to the transmitted
839+
spatial force: :math:`\|F_{resist}\| \leq \mu_s \, \|F_{spatial}\|`.
838840
839-
Mathematically, this means that: :math:`F_{resist} \leq \mu F_{spatial}`, where :math:`F_{resist}`
840-
is the resisting force applied by the solver and :math:`F_{spatial}` is the spatial force
841-
transmitted from the parent body to the child body. The simulated static friction effect is therefore
842-
similar to static and Coulomb static friction.
841+
For Isaac Sim versions 5.0 and above, the static, dynamic, and viscous friction coefficients
842+
are set. The model combines Coulomb (static & dynamic) friction with a viscous term:
843+
844+
- Static friction :math:`\mu_s` defines the maximum effort that prevents motion at rest.
845+
- Dynamic friction :math:`\mu_d` applies once motion begins and remains constant during motion.
846+
- Viscous friction :math:`c_v` is a velocity-proportional resistive term.
843847
844848
Args:
845-
joint_friction_coeff: Joint static friction coefficient. Shape is (len(env_ids), len(joint_ids)).
846-
joint_ids: The joint indices to set the joint torque limits for. Defaults to None (all joints).
847-
env_ids: The environment indices to set the joint torque limits for. Defaults to None (all environments).
849+
joint_friction_coeff: Static friction coefficient :math:`\mu_s`.
850+
Shape is (len(env_ids), len(joint_ids)). Scalars are broadcast to all selections.
851+
joint_dynamic_friction_coeff: Dynamic (Coulomb) friction coefficient :math:`\mu_d`.
852+
Same shape as above. If None, the dynamic coefficient is not updated.
853+
joint_viscous_friction_coeff: Viscous friction coefficient :math:`c_v`.
854+
Same shape as above. If None, the viscous coefficient is not updated.
855+
joint_ids: The joint indices to set the friction coefficients for. Defaults to None (all joints).
856+
env_ids: The environment indices to set the friction coefficients for. Defaults to None (all environments).
848857
"""
849858
# resolve indices
850859
physx_env_ids = env_ids
@@ -858,15 +867,38 @@ def write_joint_friction_coefficient_to_sim(
858867
env_ids = env_ids[:, None]
859868
# set into internal buffers
860869
self._data.joint_friction_coeff[env_ids, joint_ids] = joint_friction_coeff
870+
871+
# if dynamic or viscous friction coeffs are provided, set them too
872+
if joint_dynamic_friction_coeff is not None:
873+
self._data.joint_dynamic_friction_coeff[env_ids, joint_ids] = joint_dynamic_friction_coeff
874+
if joint_viscous_friction_coeff is not None:
875+
self._data.joint_viscous_friction_coeff[env_ids, joint_ids] = joint_viscous_friction_coeff
876+
877+
# move the indices to cpu
878+
physx_envs_ids_cpu = physx_env_ids.cpu()
879+
861880
# set into simulation
862881
if int(get_version()[2]) < 5:
863882
self.root_physx_view.set_dof_friction_coefficients(
864-
self._data.joint_friction_coeff.cpu(), indices=physx_env_ids.cpu()
883+
self._data.joint_friction_coeff.cpu(), indices=physx_envs_ids_cpu
865884
)
866885
else:
867886
friction_props = self.root_physx_view.get_dof_friction_properties()
868-
friction_props[physx_env_ids.cpu(), :, 0] = self._data.joint_friction_coeff[physx_env_ids, :].cpu()
869-
self.root_physx_view.set_dof_friction_properties(friction_props, indices=physx_env_ids.cpu())
887+
friction_props[physx_envs_ids_cpu, :, 0] = self._data.joint_friction_coeff[physx_envs_ids_cpu, :].cpu()
888+
889+
# only set dynamic and viscous friction if provided
890+
if joint_dynamic_friction_coeff is not None:
891+
friction_props[physx_envs_ids_cpu, :, 1] = self._data.joint_dynamic_friction_coeff[
892+
physx_envs_ids_cpu, :
893+
].cpu()
894+
895+
# only set viscous friction if provided
896+
if joint_viscous_friction_coeff is not None:
897+
friction_props[physx_envs_ids_cpu, :, 2] = self._data.joint_viscous_friction_coeff[
898+
physx_envs_ids_cpu, :
899+
].cpu()
900+
901+
self.root_physx_view.set_dof_friction_properties(friction_props, indices=physx_envs_ids_cpu)
870902

871903
def write_joint_dynamic_friction_coefficient_to_sim(
872904
self,

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

Lines changed: 49 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -714,8 +714,56 @@ def __call__(
714714
operation=operation,
715715
distribution=distribution,
716716
)
717+
718+
# ensure the friction coefficient is non-negative
719+
friction_coeff = torch.clamp(friction_coeff, min=0.0)
720+
721+
# Always set static friction (indexed once)
722+
static_friction_coeff = friction_coeff[env_ids[:, None], joint_ids]
723+
724+
# if isaacsim version is lower than 5.0.0 we can set only the static friction coefficient
725+
major_version = int(env.sim.get_version()[0])
726+
if major_version >= 5:
727+
# Randomize raw tensors
728+
dynamic_friction_coeff = _randomize_prop_by_op(
729+
self.asset.data.default_joint_dynamic_friction_coeff.clone(),
730+
friction_distribution_params,
731+
env_ids,
732+
joint_ids,
733+
operation=operation,
734+
distribution=distribution,
735+
)
736+
viscous_friction_coeff = _randomize_prop_by_op(
737+
self.asset.data.default_joint_viscous_friction_coeff.clone(),
738+
friction_distribution_params,
739+
env_ids,
740+
joint_ids,
741+
operation=operation,
742+
distribution=distribution,
743+
)
744+
745+
# Clamp to non-negative
746+
dynamic_friction_coeff = torch.clamp(dynamic_friction_coeff, min=0.0)
747+
viscous_friction_coeff = torch.clamp(viscous_friction_coeff, min=0.0)
748+
749+
# Ensure dynamic ≤ static (same shape before indexing)
750+
dynamic_friction_coeff = torch.minimum(dynamic_friction_coeff, friction_coeff)
751+
752+
# Index once at the end
753+
dynamic_friction_coeff = dynamic_friction_coeff[env_ids[:, None], joint_ids]
754+
viscous_friction_coeff = viscous_friction_coeff[env_ids[:, None], joint_ids]
755+
else:
756+
# For versions < 5.0.0, we do not set these values
757+
dynamic_friction_coeff = None
758+
viscous_friction_coeff = None
759+
760+
# Single write call for all versions
717761
self.asset.write_joint_friction_coefficient_to_sim(
718-
friction_coeff[env_ids[:, None], joint_ids], joint_ids=joint_ids, env_ids=env_ids
762+
joint_friction_coeff=static_friction_coeff,
763+
joint_dynamic_friction_coeff=dynamic_friction_coeff,
764+
joint_viscous_friction_coeff=viscous_friction_coeff,
765+
joint_ids=joint_ids,
766+
env_ids=env_ids,
719767
)
720768

721769
# joint armature

source/isaaclab/test/assets/test_articulation.py

Lines changed: 59 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1997,10 +1997,16 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground
19971997
dynamic_friction = torch.rand(num_articulations, articulation.num_joints, device=device)
19981998
viscous_friction = torch.rand(num_articulations, articulation.num_joints, device=device)
19991999
friction = torch.rand(num_articulations, articulation.num_joints, device=device)
2000+
2001+
# Guarantee that the dynamic friction is not greater than the static friction
2002+
dynamic_friction = torch.min(dynamic_friction, friction)
2003+
2004+
# The static friction must be set first to be sure the dynamic friction is not greater than static
2005+
# when both are set.
2006+
articulation.write_joint_friction_coefficient_to_sim(friction)
20002007
if int(get_version()[2]) >= 5:
20012008
articulation.write_joint_dynamic_friction_coefficient_to_sim(dynamic_friction)
20022009
articulation.write_joint_viscous_friction_coefficient_to_sim(viscous_friction)
2003-
articulation.write_joint_friction_coefficient_to_sim(friction)
20042010
articulation.write_data_to_sim()
20052011

20062012
for _ in range(100):
@@ -2010,9 +2016,58 @@ def test_write_joint_frictions_to_sim(sim, num_articulations, device, add_ground
20102016
articulation.update(sim.cfg.dt)
20112017

20122018
if int(get_version()[2]) >= 5:
2013-
assert torch.allclose(articulation.data.joint_dynamic_friction_coeff, dynamic_friction)
2014-
assert torch.allclose(articulation.data.joint_viscous_friction_coeff, viscous_friction)
2015-
assert torch.allclose(articulation.data.joint_friction_coeff, friction)
2019+
friction_props_from_sim = articulation.root_physx_view.get_dof_friction_properties()
2020+
joint_friction_coeff_sim = friction_props_from_sim[:, :, 0]
2021+
joint_dynamic_friction_coeff_sim = friction_props_from_sim[:, :, 1]
2022+
joint_viscous_friction_coeff_sim = friction_props_from_sim[:, :, 2]
2023+
assert torch.allclose(joint_dynamic_friction_coeff_sim, dynamic_friction.cpu())
2024+
assert torch.allclose(joint_viscous_friction_coeff_sim, viscous_friction.cpu())
2025+
else:
2026+
joint_friction_coeff_sim = articulation.root_physx_view.get_dof_friction_properties()
2027+
2028+
assert torch.allclose(joint_friction_coeff_sim, friction.cpu())
2029+
2030+
# For Isaac Sim >= 5.0: also test the combined API that can set dynamic and viscous via
2031+
# write_joint_friction_coefficient_to_sim; reset the sim to isolate this path.
2032+
if int(get_version()[2]) >= 5:
2033+
# Reset simulator to ensure a clean state for the alternative API path
2034+
sim.reset()
2035+
2036+
# Warm up a few steps to populate buffers
2037+
for _ in range(100):
2038+
sim.step()
2039+
articulation.update(sim.cfg.dt)
2040+
2041+
# New random coefficients
2042+
dynamic_friction_2 = torch.rand(num_articulations, articulation.num_joints, device=device)
2043+
viscous_friction_2 = torch.rand(num_articulations, articulation.num_joints, device=device)
2044+
friction_2 = torch.rand(num_articulations, articulation.num_joints, device=device)
2045+
2046+
# Guarantee that the dynamic friction is not greater than the static friction
2047+
dynamic_friction_2 = torch.min(dynamic_friction_2, friction_2)
2048+
2049+
# Use the combined setter to write all three at once
2050+
articulation.write_joint_friction_coefficient_to_sim(
2051+
joint_friction_coeff=friction_2,
2052+
joint_dynamic_friction_coeff=dynamic_friction_2,
2053+
joint_viscous_friction_coeff=viscous_friction_2,
2054+
)
2055+
articulation.write_data_to_sim()
2056+
2057+
# Step to let sim ingest new params and refresh data buffers
2058+
for _ in range(100):
2059+
sim.step()
2060+
articulation.update(sim.cfg.dt)
2061+
2062+
friction_props_from_sim_2 = articulation.root_physx_view.get_dof_friction_properties()
2063+
joint_friction_coeff_sim_2 = friction_props_from_sim_2[:, :, 0]
2064+
friction_dynamic_coef_sim_2 = friction_props_from_sim_2[:, :, 1]
2065+
friction_viscous_coeff_sim_2 = friction_props_from_sim_2[:, :, 2]
2066+
2067+
# Validate values propagated
2068+
assert torch.allclose(friction_viscous_coeff_sim_2, viscous_friction_2.cpu())
2069+
assert torch.allclose(friction_dynamic_coef_sim_2, dynamic_friction_2.cpu())
2070+
assert torch.allclose(joint_friction_coeff_sim_2, friction_2.cpu())
20162071

20172072

20182073
if __name__ == "__main__":

0 commit comments

Comments
 (0)