Skip to content

Commit d6004fd

Browse files
committed
Refactor Actuator Configs to avoid circular import.
1 parent ec38e60 commit d6004fd

File tree

18 files changed

+337
-18
lines changed

18 files changed

+337
-18
lines changed

CONTRIBUTORS.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,7 @@ Guidelines for modifications:
3535
* Pascal Roth
3636
* Sheikh Dawood
3737
* Ossama Ahmed
38+
* Brian McCann
3839

3940
## Contributors
4041

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.48.0"
4+
version = "0.48.1"
55

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

source/isaaclab/docs/CHANGELOG.rst

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

4+
0.48.1 (2025-11-10)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Changed
8+
^^^^^^^
9+
10+
* Refactored modules related to the actuator configs in order to remediate a circular import necessary to support future
11+
actuator drive model improvements.
12+
413
0.48.0 (2025-11-03)
514
~~~~~~~~~~~~~~~~~~~
615

source/isaaclab/isaaclab/actuators/__init__.py

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -23,15 +23,14 @@
2323
"""
2424

2525
from .actuator_base import ActuatorBase
26-
from .actuator_cfg import (
27-
ActuatorBaseCfg,
28-
ActuatorNetLSTMCfg,
29-
ActuatorNetMLPCfg,
26+
from .actuator_base_cfg import ActuatorBaseCfg
27+
from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP
28+
from .actuator_net_cfg import ActuatorNetLSTMCfg, ActuatorNetMLPCfg
29+
from .actuator_pd import DCMotor, DelayedPDActuator, IdealPDActuator, ImplicitActuator, RemotizedPDActuator
30+
from .actuator_pd_cfg import (
3031
DCMotorCfg,
3132
DelayedPDActuatorCfg,
3233
IdealPDActuatorCfg,
3334
ImplicitActuatorCfg,
3435
RemotizedPDActuatorCfg,
3536
)
36-
from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP
37-
from .actuator_pd import DCMotor, DelayedPDActuator, IdealPDActuator, ImplicitActuator, RemotizedPDActuator

source/isaaclab/isaaclab/actuators/actuator_base.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
from isaaclab.utils.types import ArticulationActions
1515

1616
if TYPE_CHECKING:
17-
from .actuator_cfg import ActuatorBaseCfg
17+
from .actuator_base_cfg import ActuatorBaseCfg
1818

1919

2020
class ActuatorBase(ABC):
Lines changed: 165 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,165 @@
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+
from dataclasses import MISSING
7+
8+
from isaaclab.utils import configclass
9+
10+
11+
@configclass
12+
class ActuatorBaseCfg:
13+
"""Configuration for default actuators in an articulation."""
14+
15+
class_type: type = MISSING
16+
"""The associated actuator class.
17+
18+
The class should inherit from :class:`isaaclab.actuators.ActuatorBase`.
19+
"""
20+
21+
joint_names_expr: list[str] = MISSING
22+
"""Articulation's joint names that are part of the group.
23+
24+
Note:
25+
This can be a list of joint names or a list of regex expressions (e.g. ".*").
26+
"""
27+
28+
effort_limit: dict[str, float] | float | None = None
29+
"""Force/Torque limit of the joints in the group. Defaults to None.
30+
31+
This limit is used to clip the computed torque sent to the simulation. If None, the
32+
limit is set to the value specified in the USD joint prim.
33+
34+
.. attention::
35+
36+
The :attr:`effort_limit_sim` attribute should be used to set the effort limit for
37+
the simulation physics solver.
38+
39+
The :attr:`effort_limit` attribute is used for clipping the effort output of the
40+
actuator model **only** in the case of explicit actuators, such as the
41+
:class:`~isaaclab.actuators.IdealPDActuator`.
42+
43+
.. note::
44+
45+
For implicit actuators, the attributes :attr:`effort_limit` and :attr:`effort_limit_sim`
46+
are equivalent. However, we suggest using the :attr:`effort_limit_sim` attribute because
47+
it is more intuitive.
48+
49+
"""
50+
51+
velocity_limit: dict[str, float] | float | None = None
52+
"""Velocity limit of the joints in the group. Defaults to None.
53+
54+
This limit is used by the actuator model. If None, the limit is set to the value specified
55+
in the USD joint prim.
56+
57+
.. attention::
58+
59+
The :attr:`velocity_limit_sim` attribute should be used to set the velocity limit for
60+
the simulation physics solver.
61+
62+
The :attr:`velocity_limit` attribute is used for clipping the effort output of the
63+
actuator model **only** in the case of explicit actuators, such as the
64+
:class:`~isaaclab.actuators.IdealPDActuator`.
65+
66+
.. note::
67+
68+
For implicit actuators, the attribute :attr:`velocity_limit` is not used. This is to stay
69+
backwards compatible with previous versions of the Isaac Lab, where this parameter was
70+
unused since PhysX did not support setting the velocity limit for the joints using the
71+
PhysX Tensor API.
72+
"""
73+
74+
effort_limit_sim: dict[str, float] | float | None = None
75+
"""Effort limit of the joints in the group applied to the simulation physics solver. Defaults to None.
76+
77+
The effort limit is used to constrain the computed joint efforts in the physics engine. If the
78+
computed effort exceeds this limit, the physics engine will clip the effort to this value.
79+
80+
Since explicit actuators (e.g. DC motor), compute and clip the effort in the actuator model, this
81+
limit is by default set to a large value to prevent the physics engine from any additional clipping.
82+
However, at times, it may be necessary to set this limit to a smaller value as a safety measure.
83+
84+
If None, the limit is resolved based on the type of actuator model:
85+
86+
* For implicit actuators, the limit is set to the value specified in the USD joint prim.
87+
* For explicit actuators, the limit is set to 1.0e9.
88+
89+
"""
90+
91+
velocity_limit_sim: dict[str, float] | float | None = None
92+
"""Velocity limit of the joints in the group applied to the simulation physics solver. Defaults to None.
93+
94+
The velocity limit is used to constrain the joint velocities in the physics engine. The joint will only
95+
be able to reach this velocity if the joint's effort limit is sufficiently large. If the joint is moving
96+
faster than this velocity, the physics engine will actually try to brake the joint to reach this velocity.
97+
98+
If None, the limit is set to the value specified in the USD joint prim for both implicit and explicit actuators.
99+
100+
.. tip::
101+
If the velocity limit is too tight, the physics engine may have trouble converging to a solution.
102+
In such cases, we recommend either keeping this value sufficiently large or tuning the stiffness and
103+
damping parameters of the joint to ensure the limits are not violated.
104+
105+
"""
106+
107+
stiffness: dict[str, float] | float | None = MISSING
108+
"""Stiffness gains (also known as p-gain) of the joints in the group.
109+
110+
The behavior of the stiffness is different for implicit and explicit actuators. For implicit actuators,
111+
the stiffness gets set into the physics engine directly. For explicit actuators, the stiffness is used
112+
by the actuator model to compute the joint efforts.
113+
114+
If None, the stiffness is set to the value from the USD joint prim.
115+
"""
116+
117+
damping: dict[str, float] | float | None = MISSING
118+
"""Damping gains (also known as d-gain) of the joints in the group.
119+
120+
The behavior of the damping is different for implicit and explicit actuators. For implicit actuators,
121+
the damping gets set into the physics engine directly. For explicit actuators, the damping gain is used
122+
by the actuator model to compute the joint efforts.
123+
124+
If None, the damping is set to the value from the USD joint prim.
125+
"""
126+
127+
armature: dict[str, float] | float | None = None
128+
"""Armature of the joints in the group. Defaults to None.
129+
130+
The armature is directly added to the corresponding joint-space inertia. It helps improve the
131+
simulation stability by reducing the joint velocities.
132+
133+
It is a physics engine solver parameter that gets set into the simulation.
134+
135+
If None, the armature is set to the value from the USD joint prim.
136+
"""
137+
138+
friction: dict[str, float] | float | None = None
139+
r"""The static friction coefficient of the joints in the group. Defaults to None.
140+
141+
The joint static friction is a unitless quantity. It relates the magnitude of the spatial force transmitted
142+
from the parent body to the child body to the maximal static friction force that may be applied by the solver
143+
to resist the joint motion.
144+
145+
Mathematically, this means that: :math:`F_{resist} \leq \mu F_{spatial}`, where :math:`F_{resist}`
146+
is the resisting force applied by the solver and :math:`F_{spatial}` is the spatial force
147+
transmitted from the parent body to the child body. The simulated static friction effect is therefore
148+
similar to static and Coulomb static friction.
149+
150+
If None, the joint static friction is set to the value from the USD joint prim.
151+
152+
Note: In Isaac Sim 4.5, this parameter is modeled as a coefficient. In Isaac Sim 5.0 and later,
153+
it is modeled as an effort (torque or force).
154+
"""
155+
156+
dynamic_friction: dict[str, float] | float | None = None
157+
"""The dynamic friction coefficient of the joints in the group. Defaults to None.
158+
159+
Note: In Isaac Sim 4.5, this parameter is modeled as a coefficient. In Isaac Sim 5.0 and later,
160+
it is modeled as an effort (torque or force).
161+
"""
162+
163+
viscous_friction: dict[str, float] | float | None = None
164+
"""The viscous friction coefficient of the joints in the group. Defaults to None.
165+
"""

source/isaaclab/isaaclab/actuators/actuator_net.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
from .actuator_pd import DCMotor
2525

2626
if TYPE_CHECKING:
27-
from .actuator_cfg import ActuatorNetLSTMCfg, ActuatorNetMLPCfg
27+
from .actuator_net_cfg import ActuatorNetLSTMCfg, ActuatorNetMLPCfg
2828

2929

3030
class ActuatorNetLSTM(DCMotor):
Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
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+
from collections.abc import Iterable
7+
from dataclasses import MISSING
8+
from typing import Literal
9+
10+
from isaaclab.utils import configclass
11+
12+
from . import actuator_net
13+
from .actuator_pd_cfg import DCMotorCfg
14+
15+
16+
@configclass
17+
class ActuatorNetLSTMCfg(DCMotorCfg):
18+
"""Configuration for LSTM-based actuator model."""
19+
20+
class_type: type = actuator_net.ActuatorNetLSTM
21+
# we don't use stiffness and damping for actuator net
22+
stiffness = None
23+
damping = None
24+
25+
network_file: str = MISSING
26+
"""Path to the file containing network weights."""
27+
28+
29+
@configclass
30+
class ActuatorNetMLPCfg(DCMotorCfg):
31+
"""Configuration for MLP-based actuator model."""
32+
33+
class_type: type = actuator_net.ActuatorNetMLP
34+
# we don't use stiffness and damping for actuator net
35+
36+
stiffness = None
37+
damping = None
38+
39+
network_file: str = MISSING
40+
"""Path to the file containing network weights."""
41+
42+
pos_scale: float = MISSING
43+
"""Scaling of the joint position errors input to the network."""
44+
vel_scale: float = MISSING
45+
"""Scaling of the joint velocities input to the network."""
46+
torque_scale: float = MISSING
47+
"""Scaling of the joint efforts output from the network."""
48+
49+
input_order: Literal["pos_vel", "vel_pos"] = MISSING
50+
"""Order of the inputs to the network.
51+
52+
The order can be one of the following:
53+
54+
* ``"pos_vel"``: joint position errors followed by joint velocities
55+
* ``"vel_pos"``: joint velocities followed by joint position errors
56+
"""
57+
58+
input_idx: Iterable[int] = MISSING
59+
"""
60+
Indices of the actuator history buffer passed as inputs to the network.
61+
62+
The index *0* corresponds to current time-step, while *n* corresponds to n-th
63+
time-step in the past. The allocated history length is `max(input_idx) + 1`.
64+
"""

source/isaaclab/isaaclab/actuators/actuator_pd.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
from .actuator_base import ActuatorBase
1717

1818
if TYPE_CHECKING:
19-
from .actuator_cfg import (
19+
from .actuator_pd_cfg import (
2020
DCMotorCfg,
2121
DelayedPDActuatorCfg,
2222
IdealPDActuatorCfg,
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
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+
from dataclasses import MISSING
7+
8+
from isaaclab.utils import configclass
9+
10+
from . import actuator_pd
11+
from .actuator_base_cfg import ActuatorBaseCfg
12+
13+
"""
14+
Implicit Actuator Models.
15+
"""
16+
17+
18+
@configclass
19+
class ImplicitActuatorCfg(ActuatorBaseCfg):
20+
"""Configuration for an implicit actuator.
21+
22+
Note:
23+
The PD control is handled implicitly by the simulation.
24+
"""
25+
26+
class_type: type = actuator_pd.ImplicitActuator
27+
28+
29+
"""
30+
Explicit Actuator Models.
31+
"""
32+
33+
34+
@configclass
35+
class IdealPDActuatorCfg(ActuatorBaseCfg):
36+
"""Configuration for an ideal PD actuator."""
37+
38+
class_type: type = actuator_pd.IdealPDActuator
39+
40+
41+
@configclass
42+
class DCMotorCfg(IdealPDActuatorCfg):
43+
"""Configuration for direct control (DC) motor actuator model."""
44+
45+
class_type: type = actuator_pd.DCMotor
46+
47+
saturation_effort: float = MISSING
48+
"""Peak motor force/torque of the electric DC motor (in N-m)."""
49+
50+
51+
@configclass
52+
class DelayedPDActuatorCfg(IdealPDActuatorCfg):
53+
"""Configuration for a delayed PD actuator."""
54+
55+
class_type: type = actuator_pd.DelayedPDActuator
56+
57+
min_delay: int = 0
58+
"""Minimum number of physics time-steps with which the actuator command may be delayed. Defaults to 0."""
59+
60+
max_delay: int = 0
61+
"""Maximum number of physics time-steps with which the actuator command may be delayed. Defaults to 0."""
62+
63+
64+
@configclass
65+
class RemotizedPDActuatorCfg(DelayedPDActuatorCfg):
66+
"""Configuration for a remotized PD actuator.
67+
68+
Note:
69+
The torque output limits for this actuator is derived from a linear interpolation of a lookup table
70+
in :attr:`joint_parameter_lookup`. This table describes the relationship between joint angles and
71+
the output torques.
72+
"""
73+
74+
class_type: type = actuator_pd.RemotizedPDActuator
75+
76+
joint_parameter_lookup: list[list[float]] = MISSING
77+
"""Joint parameter lookup table. Shape is (num_lookup_points, 3).
78+
79+
This tensor describes the relationship between the joint angle (rad), the transmission ratio (in/out),
80+
and the output torque (N*m). The table is used to interpolate the output torque based on the joint angle.
81+
"""

0 commit comments

Comments
 (0)