Skip to content

Commit d1932bf

Browse files
committed
parent 7e8ebe6
author Brian McCann <[email protected]> 1762808364 -0500 committer Brian McCann <[email protected]> 1762808383 -0500 This change implements the necessary changes to the articulation and actuator classes in order to configure the new actuator drive model including velocity and effort dependent constraints on motor actuation. For details see https://nvidia-omniverse.github.io/PhysX/physx/5.6.1/docs/Articulations.html#articulation-drive-stability and https://docs.omniverse.nvidia.com/kit/docs/omni_physics/latest/extensions/runtime/source/omni.physics.tensors/docs/api/python.html#omni.physics.tensors.impl.api.ArticulationView.set_dof_drive_model_properties
1 parent 0dfbf47 commit d1932bf

File tree

11 files changed

+412
-320
lines changed

11 files changed

+412
-320
lines changed

docs/source/api/lab/isaaclab.actuators.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,9 @@ Actuator Base
3636
:inherited-members:
3737
:exclude-members: __init__, class_type
3838

39+
.. autoclass:: isaaclab.actuators.actuator_base_cfg.ActuatorBaseCfg.DriveModelCfg
40+
:members:
41+
3942
Implicit Actuator
4043
-----------------
4144

scripts/get_omni_version.py

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
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+
import omni.kit.app
7+
8+
from isaaclab.app import AppLauncher
9+
10+
app_launcher = AppLauncher(headless=True, enable_cameras=True)
11+
simulation_app = app_launcher.app
12+
13+
app = omni.kit.app.get_app()
14+
kit_version = app.get_kit_version()
15+
print(kit_version)

source/isaaclab/config/extension.toml

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

33
# Note: Semantic Versioning is used: https://semver.org/
4-
version = "0.48.1"
4+
5+
version = "0.48.2"
56

67
# Description
78
title = "Isaac Lab framework for Robot Learning"

source/isaaclab/docs/CHANGELOG.rst

Lines changed: 26 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,25 @@
11
Changelog
22
---------
33

4-
0.48.1 (2025-11-10)
4+
0.48.2 (2025-11-10)
55
~~~~~~~~~~~~~~~~~~~
66

7-
Changed
8-
^^^^^^^
7+
Added
8+
^^^^^
9+
10+
* Implemented drive model improvements for implicit actuators allowing them to configure a new feature within physx to apply
11+
constraints on actuator effort dependent on the torque and velocity on the articulation.
12+
* Introduced a NamedTuple config classes as a way to organize related parameters, and extended the configuration parsing to
13+
work with related (mutually dependent) parameters in the configurations.
914

10-
* Refactored modules related to the actuator configs in order to remediate a circular import necessary to support future
11-
actuator drive model improvements.
15+
0.48.1 (2025-11-10)
16+
~~~~~~~~~~~~~~~~~~~
17+
18+
Changed
19+
^^^^^^^
20+
21+
* Refactored modules related to the actuator configs in order to remediate a circular import necessary to support future
22+
actuator drive model improvements.
1223

1324
0.48.0 (2025-11-03)
1425
~~~~~~~~~~~~~~~~~~~
@@ -71,6 +82,16 @@ Added
7182

7283
* Added parameter :attr:`~isaaclab.terrains.TerrainImporterCfg.use_terrain_origins` to allow generated sub terrains with grid origins.
7384

85+
0.48.2 (2025-11-10)
86+
~~~~~~~~~~~~~~~~~~
87+
88+
Added
89+
^^^^^
90+
91+
* Implemented drive model improvements for implicit actuators allowing them to configure a new feature within physx to apply
92+
constraints on actuator effort dependent on the torque and velocity on the articulation.
93+
* Introduced a NamedTuple config classes as a way to organize related parameters, and extended the configuration parsing to
94+
work with related (mutually dependent) parameters in the configurations.
7495

7596
0.47.7 (2025-10-31)
7697
~~~~~~~~~~~~~~~~~~~

source/isaaclab/isaaclab/actuators/actuator_base.py

Lines changed: 116 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -8,13 +8,17 @@
88
import torch
99
from abc import ABC, abstractmethod
1010
from collections.abc import Sequence
11-
from typing import TYPE_CHECKING, ClassVar
11+
from typing import ClassVar
1212

1313
import isaaclab.utils.string as string_utils
1414
from isaaclab.utils.types import ArticulationActions
1515

16+
<<<<<<< HEAD
1617
if TYPE_CHECKING:
1718
from .actuator_base_cfg import ActuatorBaseCfg
19+
=======
20+
from .actuator_base_cfg import ActuatorBaseCfg
21+
>>>>>>> ed1544b8ca (parent 7e8ebe67ef3e3c280eb3fda39443d643317fdeca)
1822

1923

2024
class ActuatorBase(ABC):
@@ -84,6 +88,18 @@ class ActuatorBase(ABC):
8488
For implicit actuators, the :attr:`velocity_limit` and :attr:`velocity_limit_sim` are the same.
8589
"""
8690

91+
drive_model: torch.Tensor
92+
"""Three parameters for each joint/env defining the:
93+
(1) [:,:,0] speed_effort_gradient : float = 1 (default),
94+
(2) [:,:,1] maximum_actuator_velocity : float = torch.inf (default), and
95+
(3) [:,:,2] velocity_dependent_resistance : float = 1 (default)
96+
97+
which define velocity and effort dependent constraints on the motor's performance.
98+
99+
This feature is only implemented in IsaacSim v5.0.
100+
101+
The shape is (num_envs, num_joints, 3)."""
102+
87103
stiffness: torch.Tensor
88104
"""The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints)."""
89105

@@ -124,6 +140,7 @@ def __init__(
124140
viscous_friction: torch.Tensor | float = 0.0,
125141
effort_limit: torch.Tensor | float = torch.inf,
126142
velocity_limit: torch.Tensor | float = torch.inf,
143+
drive_model: torch.Tensor | tuple[float, float, float] = ActuatorBaseCfg.DriveModelCfg(),
127144
):
128145
"""Initialize the actuator.
129146
@@ -160,6 +177,9 @@ def __init__(
160177
If a tensor, then the shape is (num_envs, num_joints).
161178
velocity_limit: The default velocity limit. Defaults to infinity.
162179
If a tensor, then the shape is (num_envs, num_joints).
180+
drive_model: Drive model for the actuator including speed_effort_gradient, max_actuator_velocity, and
181+
velocity_dependent_resistance in that order. Defaults to (0.0, torch.inf, 0.0).
182+
If a tensor then the shape is (num_envs, num_joints, 3).
163183
"""
164184
# save parameters
165185
self.cfg = cfg
@@ -187,19 +207,32 @@ def __init__(
187207
("friction", friction),
188208
("dynamic_friction", dynamic_friction),
189209
("viscous_friction", viscous_friction),
210+
("drive_model", drive_model, 3),
190211
]
191-
for param_name, usd_val in to_check:
212+
for param_name, usd_val, *tuple_len in to_check:
213+
# check if the parameter requires a tuple or a single float
214+
if len(tuple_len) > 0:
215+
shape = (self._num_envs, self.num_joints, tuple_len[0])
216+
else:
217+
shape = (self._num_envs, self.num_joints)
218+
192219
cfg_val = getattr(self.cfg, param_name)
193-
setattr(self, param_name, self._parse_joint_parameter(cfg_val, usd_val))
220+
setattr(self, param_name, self._parse_joint_parameter(cfg_val, usd_val, shape, param_name=param_name))
194221
new_val = getattr(self, param_name)
195222

196223
allclose = (
197-
torch.all(new_val == usd_val) if isinstance(usd_val, (float, int)) else torch.allclose(new_val, usd_val)
224+
torch.all(new_val == usd_val)
225+
if isinstance(usd_val, (float, int))
226+
else (
227+
all([torch.all(new_val[:, :, i] == float(v)) for i, v in enumerate(usd_val)])
228+
if isinstance(usd_val, tuple)
229+
else torch.allclose(new_val, usd_val)
230+
)
198231
)
199232
if cfg_val is None or not allclose:
200233
self._record_actuator_resolution(
201234
cfg_val=getattr(self.cfg, param_name),
202-
new_val=new_val[0], # new val always has the shape of (num_envs, num_joints)
235+
new_val=new_val[0],
203236
usd_val=usd_val,
204237
joint_names=joint_names,
205238
joint_ids=joint_ids,
@@ -303,20 +336,35 @@ def _record_actuator_resolution(self, cfg_val, new_val, usd_val, joint_names, jo
303336

304337
ids = joint_ids if isinstance(joint_ids, torch.Tensor) else list(range(len(joint_names)))
305338
for idx, name in enumerate(joint_names):
306-
cfg_val_log = "Not Specified" if cfg_val is None else float(new_val[idx])
307-
default_usd_val = usd_val if isinstance(usd_val, (float, int)) else float(usd_val[0][idx])
308-
applied_val_log = default_usd_val if cfg_val is None else float(new_val[idx])
309-
table.append([name, int(ids[idx]), default_usd_val, cfg_val_log, applied_val_log])
339+
if len(new_val.shape) == 1:
340+
cfg_val_log = "Not Specified" if cfg_val is None else float(new_val[idx])
341+
default_usd_val = usd_val if isinstance(usd_val, (float, int)) else float(usd_val[0][idx])
342+
applied_val_log = default_usd_val if cfg_val is None else float(new_val[idx])
343+
table.append([name, int(ids[idx]), default_usd_val, cfg_val_log, applied_val_log])
344+
else:
345+
cfg_val_log = "Not Specified" if cfg_val is None else tuple(new_val[idx])
346+
default_usd_val = usd_val if isinstance(usd_val, (tuple)) else tuple(usd_val[0][idx][:])
347+
applied_val_log = default_usd_val if cfg_val is None else tuple(new_val[idx])
348+
table.append([name, int(ids[idx]), default_usd_val, cfg_val_log, applied_val_log])
310349

311350
def _parse_joint_parameter(
312-
self, cfg_value: float | dict[str, float] | None, default_value: float | torch.Tensor | None
351+
self,
352+
cfg_value: tuple[float, ...] | dict[str, tuple[float, ...]] | float | dict[str, float] | None,
353+
default_value: tuple[float, ...] | float | torch.Tensor | None,
354+
expected_shape: tuple[int, ...] | None = None,
355+
*,
356+
param_name: str = "No name specified",
313357
) -> torch.Tensor:
314358
"""Parse the joint parameter from the configuration.
315359
316360
Args:
317361
cfg_value: The parameter value from the configuration. If None, then use the default value.
318362
default_value: The default value to use if the parameter is None. If it is also None,
319363
then an error is raised.
364+
expected_shape: The expected shape for the tensor buffer. Usually defaults to (num_envs, num_joints).
365+
366+
Kwargs:
367+
param_name: a string with the parameter name. (Optional used only in exception messages).
320368
321369
Returns:
322370
The parsed parameter value.
@@ -325,38 +373,87 @@ def _parse_joint_parameter(
325373
TypeError: If the parameter value is not of the expected type.
326374
TypeError: If the default value is not of the expected type.
327375
ValueError: If the parameter value is None and no default value is provided.
328-
ValueError: If the default value tensor is the wrong shape.
376+
ValueError: If a tensor or tuple is the wrong shape.
329377
"""
378+
if expected_shape is None:
379+
expected_shape = (self._num_envs, self.num_joints)
330380
# create parameter buffer
331-
param = torch.zeros(self._num_envs, self.num_joints, device=self._device)
381+
param = torch.zeros(*expected_shape, device=self._device)
382+
332383
# parse the parameter
333384
if cfg_value is not None:
334385
if isinstance(cfg_value, (float, int)):
335386
# if float, then use the same value for all joints
336387
param[:] = float(cfg_value)
388+
elif isinstance(cfg_value, tuple):
389+
# if tuple, ensure we expect a tuple for this parameter
390+
if len(expected_shape) < 3:
391+
raise TypeError(
392+
f"Invalid type for parameter value: {type(cfg_value)} for parameter {param_name}"
393+
+ f" actuator on joints {self.joint_names}. Expected float or dict, got tuple"
394+
)
395+
# ensure the tuple is the correct length, and assign to the last tensor dimensions across all joints
396+
if not len(cfg_value) == expected_shape[2]:
397+
raise ValueError(
398+
f"Invalid tuple length for parameter {param_name}, got {len(cfg_value)}, expected"
399+
+ f" {expected_shape[2]}"
400+
)
401+
for i, v in enumerate(cfg_value):
402+
param[:, :, i] = float(v)
337403
elif isinstance(cfg_value, dict):
338404
# if dict, then parse the regular expression
339-
indices, _, values = string_utils.resolve_matching_names_values(cfg_value, self.joint_names)
340-
# note: need to specify type to be safe (e.g. values are ints, but we want floats)
341-
param[:, indices] = torch.tensor(values, dtype=torch.float, device=self._device)
405+
indices, j, values = string_utils.resolve_matching_names_values(cfg_value, self.joint_names)
406+
# if the expected shape has two dimensions, we expect floats
407+
if len(expected_shape) < 3:
408+
# note: need to specify type to be safe (e.g. values are ints, but we want floats)
409+
param[:, indices] = torch.tensor(values, dtype=torch.float, device=self._device)
410+
# otherwise, we expect tuples
411+
else:
412+
# We can't directly assign tuples to tensors, so iterate through them
413+
for i, v in enumerate(values):
414+
# Raise an exception if the tuple is the incorrect length
415+
if len(v) != expected_shape[2]:
416+
raise ValueError(
417+
f"Invalid tuple length for parameter {param_name} on joint {j[i]} at index"
418+
f" {indices[i]}, "
419+
+ f"expected {expected_shape[2]} got {len(v)}."
420+
)
421+
# Otherwise iterate through the tuple, and assign the values in order.
422+
for i2, v2 in enumerate(v):
423+
param[:, indices[i], i2] = float(v2)
342424
else:
343425
raise TypeError(
344426
f"Invalid type for parameter value: {type(cfg_value)} for "
345-
+ f"actuator on joints {self.joint_names}. Expected float or dict."
427+
+ f"actuator on joints {self.joint_names}. Expected tuple, float or dict."
346428
)
347429
elif default_value is not None:
348430
if isinstance(default_value, (float, int)):
349431
# if float, then use the same value for all joints
350432
param[:] = float(default_value)
433+
elif isinstance(default_value, tuple):
434+
# if tuple, ensure we expect a tuple for this parameter
435+
if len(expected_shape) < 3:
436+
raise TypeError(
437+
f"Invalid default type for parameter value: {type(default_value)} for "
438+
+ f"actuator on joints {self.joint_names}. Expected float or dict, got tuple"
439+
)
440+
# ensure the tuple is the correct length, and assign to the last tensor dimensions across all joints
441+
if not len(default_value) == expected_shape[2]:
442+
raise ValueError(
443+
f"Invalid tuple length for parameter {param_name}, got {len(default_value)}, expected"
444+
+ f" {expected_shape[2]}"
445+
)
446+
for i, v in enumerate(default_value):
447+
param[:, :, i] = float(v)
351448
elif isinstance(default_value, torch.Tensor):
352449
# if tensor, then use the same tensor for all joints
353-
if default_value.shape == (self._num_envs, self.num_joints):
450+
if tuple(default_value.shape) == expected_shape:
354451
param = default_value.float()
355452
else:
356453
raise ValueError(
357454
"Invalid default value tensor shape.\n"
358-
f"Got: {default_value.shape}\n"
359-
f"Expected: {(self._num_envs, self.num_joints)}"
455+
+ f"Got: {tuple(default_value.shape)}\n"
456+
+ f"Expected: {expected_shape}"
360457
)
361458
else:
362459
raise TypeError(

source/isaaclab/isaaclab/actuators/actuator_base_cfg.py

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,11 @@
44
# SPDX-License-Identifier: BSD-3-Clause
55

66
from dataclasses import MISSING
7+
<<<<<<< HEAD
8+
=======
9+
from torch import inf
10+
from typing import NamedTuple
11+
>>>>>>> ed1544b8ca (parent 7e8ebe67ef3e3c280eb3fda39443d643317fdeca)
712

813
from isaaclab.utils import configclass
914

@@ -48,6 +53,21 @@ class ActuatorBaseCfg:
4853
4954
"""
5055

56+
<<<<<<< HEAD
57+
=======
58+
"""Optional (min v5) settings to the drive model capturing performance envelope velocity-effort dependence.
59+
60+
See: https://docs.omniverse.nvidia.com/kit/docs/omni_physics/107.3/_downloads/f44e831b7f29e7c2ec8e3f2c54418430/drivePerformanceEnvelope.pdf
61+
"""
62+
63+
class DriveModelCfg(NamedTuple):
64+
speed_effort_gradient: float = 0.0
65+
max_actuator_velocity: float = inf
66+
velocity_dependent_resistance: float = 0.0
67+
68+
drive_model: dict[str, DriveModelCfg] | DriveModelCfg | None = None
69+
70+
>>>>>>> ed1544b8ca (parent 7e8ebe67ef3e3c280eb3fda39443d643317fdeca)
5171
velocity_limit: dict[str, float] | float | None = None
5272
"""Velocity limit of the joints in the group. Defaults to None.
5373

0 commit comments

Comments
 (0)