Skip to content

Commit 24a78b6

Browse files
Fixes DCMotor clipping for negative power and adds actuator tests (#2300)
# Description This PR adds tests for actuator initialization, configuration, and computation for Implicit, IdealPD, and DC motor actuators. This PR also updates the DCMotor model to clip based on a four quadrant DC motor model. This will fix improper clipping in the negative power regions (i.e. positive torque and negative velocity or negative torque and positive velocity). NOTE: This PR is dependant on the pytest migration in: [2034](#2034) This PR includes changes made in [2291](#2291) and would be an alternate candidate. Fixes [#2139](#2139) <!-- 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. --> ## Type of change <!-- As you go through the list, delete the ones that are not applicable. --> - Bug fix (non-breaking change which fixes an issue) - New feature (non-breaking change which adds functionality) ## Screenshots ![image](https://github.com/user-attachments/assets/c94f877e-b3a9-441a-ad2e-ec6124cc64de) ## Checklist - [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: Kelly Guo <[email protected]> Signed-off-by: James Tigue <[email protected]> Signed-off-by: Kelly Guo <[email protected]> Co-authored-by: Kelly Guo <[email protected]> Co-authored-by: Kelly Guo <[email protected]>
1 parent ce2ae92 commit 24a78b6

File tree

9 files changed

+767
-26
lines changed

9 files changed

+767
-26
lines changed
Loading

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

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,11 @@ Ideal PD Actuator
6767
DC Motor Actuator
6868
-----------------
6969

70+
.. figure:: ../../../_static/overview/actuator-group/dc_motor_clipping.jpg
71+
:align: center
72+
:figwidth: 100%
73+
:alt: The effort clipping as a function of joint velocity for a linear DC Motor.
74+
7075
.. autoclass:: DCMotor
7176
:members:
7277
:inherited-members:

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.41.0"
4+
version = "0.41.1"
55

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

source/isaaclab/docs/CHANGELOG.rst

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

4+
0.41.1 (2025-07-22)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Added
8+
^^^^^
9+
10+
* Added unit tests for :class:`~isaaclab.actuator.ImplicitActuator`, :class:`~isaaclab.actuator.IdealPDActuator`,
11+
and :class:`~isaaclab.actuator.DCMotor` independent of :class:`~isaaclab.assets.Articulation`
12+
13+
Changed
14+
^^^^^^^
15+
16+
* Changed the way clipping is handled for :class:`~isaaclab.actuator.DCMotor` for torque-speed points in when in
17+
negative power regions.
18+
19+
420
0.41.0 (2025-07-21)
521
~~~~~~~~~~~~~~~~~~~
622

source/isaaclab/isaaclab/actuators/actuator_net.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -79,8 +79,6 @@ def compute(
7979
# compute network inputs
8080
self.sea_input[:, 0, 0] = (control_action.joint_positions - joint_pos).flatten()
8181
self.sea_input[:, 0, 1] = joint_vel.flatten()
82-
# save current joint vel for dc-motor clipping
83-
self._joint_vel[:] = joint_vel
8482

8583
# run network inference
8684
with torch.inference_mode():

source/isaaclab/isaaclab/actuators/actuator_pd.py

Lines changed: 35 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -201,8 +201,8 @@ def compute(
201201
class DCMotor(IdealPDActuator):
202202
r"""Direct control (DC) motor actuator model with velocity-based saturation model.
203203
204-
It uses the same model as the :class:`IdealActuator` for computing the torques from input commands.
205-
However, it implements a saturation model defined by DC motor characteristics.
204+
It uses the same model as the :class:`IdealPDActuator` for computing the torques from input commands.
205+
However, it implements a saturation model defined by a linear four quadrant DC motor torque-speed curve.
206206
207207
A DC motor is a type of electric motor that is powered by direct current electricity. In most cases,
208208
the motor is connected to a constant source of voltage supply, and the current is controlled by a rheostat.
@@ -211,23 +211,28 @@ class DCMotor(IdealPDActuator):
211211
212212
A DC motor characteristics are defined by the following parameters:
213213
214-
* Continuous-rated speed (:math:`\dot{q}_{motor, max}`) : The maximum-rated speed of the motor.
215-
* Continuous-stall torque (:math:`\tau_{motor, max}`): The maximum-rated torque produced at 0 speed.
216-
* Saturation torque (:math:`\tau_{motor, sat}`): The maximum torque that can be outputted for a short period.
214+
* No-load speed (:math:`\dot{q}_{motor, max}`) : The maximum-rated speed of the motor at 0 Torque (:attr:`velocity_limit`).
215+
* Stall torque (:math:`\tau_{motor, stall}`): The maximum-rated torque produced at 0 speed (:attr:`saturation_effort`).
216+
* Continuous torque (:math:`\tau_{motor, con}`): The maximum torque that can be outputted for a short period. This
217+
is often enforced on the current drives for a DC motor to limit overheating, prevent mechanical damage, or
218+
enforced by electrical limitations.(:attr:`effort_limit`).
219+
* Corner velocity (:math:`V_{c}`): The velocity where the torque-speed curve intersects with continuous torque.
220+
Based on these parameters, the instantaneous minimum and maximum torques for velocities between corner velocities
221+
(where torque-speed curve intersects with continuous torque) are defined as follows:
217222
218-
Based on these parameters, the instantaneous minimum and maximum torques are defined as follows:
223+
Based on these parameters, the instantaneous minimum and maximum torques for velocities are defined as follows:
219224
220225
.. math::
221226
222-
\tau_{j, max}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left(1 -
223-
\frac{\dot{q}}{\dot{q}_{j, max}}\right), 0.0, \tau_{j, max} \right) \\
224-
\tau_{j, min}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left( -1 -
225-
\frac{\dot{q}}{\dot{q}_{j, max}}\right), - \tau_{j, max}, 0.0 \right)
227+
\tau_{j, max}(\dot{q}) & = clip \left (\tau_{j, stall} \times \left(1 -
228+
\frac{\dot{q}}{\dot{q}_{j, max}}\right), -∞, \tau_{j, con} \right) \\
229+
\tau_{j, min}(\dot{q}) & = clip \left (\tau_{j, stall} \times \left( -1 -
230+
\frac{\dot{q}}{\dot{q}_{j, max}}\right), - \tau_{j, con}, \right)
226231
227232
where :math:`\gamma` is the gear ratio of the gear box connecting the motor and the actuated joint ends,
228-
:math:`\dot{q}_{j, max} = \gamma^{-1} \times \dot{q}_{motor, max}`, :math:`\tau_{j, max} =
229-
\gamma \times \tau_{motor, max}` and :math:`\tau_{j, peak} = \gamma \times \tau_{motor, peak}`
230-
are the maximum joint velocity, maximum joint torque and peak torque, respectively. These parameters
233+
:math:`\dot{q}_{j, max} = \gamma^{-1} \times \dot{q}_{motor, max}`, :math:`\tau_{j, con} =
234+
\gamma \times \tau_{motor, con}` and :math:`\tau_{j, stall} = \gamma \times \tau_{motor, stall}`
235+
are the maximum joint velocity, continuous joint torque and stall torque, respectively. These parameters
231236
are read from the configuration instance passed to the class.
232237
233238
Using these values, the computed torques are clipped to the minimum and maximum values based on the
@@ -237,6 +242,10 @@ class DCMotor(IdealPDActuator):
237242
238243
\tau_{j, applied} = clip(\tau_{computed}, \tau_{j, min}(\dot{q}), \tau_{j, max}(\dot{q}))
239244
245+
If the velocity of the joint is outside corner velocities (this would be due to external forces) the
246+
applied output torque will be driven to the Continuous Torque (`effort_limit`).
247+
248+
The figure below demonstrates the clipping action for example (velocity, torque) pairs.
240249
"""
241250

242251
cfg: DCMotorCfg
@@ -245,10 +254,11 @@ class DCMotor(IdealPDActuator):
245254
def __init__(self, cfg: DCMotorCfg, *args, **kwargs):
246255
super().__init__(cfg, *args, **kwargs)
247256
# parse configuration
248-
if self.cfg.saturation_effort is not None:
249-
self._saturation_effort = self.cfg.saturation_effort
250-
else:
251-
self._saturation_effort = torch.inf
257+
if self.cfg.saturation_effort is None:
258+
raise ValueError("The saturation_effort must be provided for the DC motor actuator model.")
259+
self._saturation_effort = self.cfg.saturation_effort
260+
# find the velocity on the torque-speed curve that intersects effort_limit in the second and fourth quadrant
261+
self._vel_at_effort_lim = self.velocity_limit * (1 + self.effort_limit / self._saturation_effort)
252262
# prepare joint vel buffer for max effort computation
253263
self._joint_vel = torch.zeros_like(self.computed_effort)
254264
# create buffer for zeros effort
@@ -274,16 +284,18 @@ def compute(
274284
"""
275285

276286
def _clip_effort(self, effort: torch.Tensor) -> torch.Tensor:
287+
# save current joint vel
288+
self._joint_vel[:] = torch.clip(self._joint_vel, min=-self._vel_at_effort_lim, max=self._vel_at_effort_lim)
277289
# compute torque limits
290+
torque_speed_top = self._saturation_effort * (1.0 - self._joint_vel / self.velocity_limit)
291+
torque_speed_bottom = self._saturation_effort * (-1.0 - self._joint_vel / self.velocity_limit)
278292
# -- max limit
279-
max_effort = self._saturation_effort * (1.0 - self._joint_vel / self.velocity_limit)
280-
max_effort = torch.clip(max_effort, min=self._zeros_effort, max=self.effort_limit)
293+
max_effort = torch.clip(torque_speed_top, max=self.effort_limit)
281294
# -- min limit
282-
min_effort = self._saturation_effort * (-1.0 - self._joint_vel / self.velocity_limit)
283-
min_effort = torch.clip(min_effort, min=-self.effort_limit, max=self._zeros_effort)
284-
295+
min_effort = torch.clip(torque_speed_bottom, min=-self.effort_limit)
285296
# clip the torques based on the motor limits
286-
return torch.clip(effort, min=min_effort, max=max_effort)
297+
clamped = torch.clip(effort, min=min_effort, max=max_effort)
298+
return clamped
287299

288300

289301
class DelayedPDActuator(IdealPDActuator):
Lines changed: 193 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,193 @@
1+
# Copyright (c) 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 isaaclab.app import AppLauncher
7+
8+
HEADLESS = True
9+
10+
# if not AppLauncher.instance():
11+
simulation_app = AppLauncher(headless=HEADLESS).app
12+
13+
"""Rest of imports follows"""
14+
15+
import torch
16+
17+
import pytest
18+
19+
from isaaclab.actuators import DCMotorCfg
20+
21+
22+
@pytest.mark.parametrize("num_envs", [1, 2])
23+
@pytest.mark.parametrize("num_joints", [1, 2])
24+
@pytest.mark.parametrize("device", ["cuda:0", "cpu"])
25+
def test_dc_motor_init_minimum(num_envs, num_joints, device):
26+
joint_names = [f"joint_{d}" for d in range(num_joints)]
27+
joint_ids = [d for d in range(num_joints)]
28+
stiffness = 200
29+
damping = 10
30+
effort_limit = 60.0
31+
saturation_effort = 100.0
32+
velocity_limit = 50
33+
34+
actuator_cfg = DCMotorCfg(
35+
joint_names_expr=joint_names,
36+
stiffness=stiffness,
37+
damping=damping,
38+
effort_limit=effort_limit,
39+
saturation_effort=saturation_effort,
40+
velocity_limit=velocity_limit,
41+
)
42+
# assume Articulation class:
43+
# - finds joints (names and ids) associate with the provided joint_names_expr
44+
45+
actuator = actuator_cfg.class_type(
46+
actuator_cfg,
47+
joint_names=joint_names,
48+
joint_ids=joint_ids,
49+
num_envs=num_envs,
50+
device=device,
51+
)
52+
53+
# check device and shape
54+
torch.testing.assert_close(actuator.computed_effort, torch.zeros(num_envs, num_joints, device=device))
55+
torch.testing.assert_close(actuator.applied_effort, torch.zeros(num_envs, num_joints, device=device))
56+
torch.testing.assert_close(
57+
actuator.effort_limit,
58+
effort_limit * torch.ones(num_envs, num_joints, device=device),
59+
)
60+
torch.testing.assert_close(
61+
actuator.velocity_limit, velocity_limit * torch.ones(num_envs, num_joints, device=device)
62+
)
63+
64+
65+
@pytest.mark.parametrize("num_envs", [1, 2])
66+
@pytest.mark.parametrize("num_joints", [1, 2])
67+
@pytest.mark.parametrize("device", ["cuda", "cpu"])
68+
@pytest.mark.parametrize("test_point", range(20))
69+
def test_dc_motor_clip(num_envs, num_joints, device, test_point):
70+
r"""Test the computation of the dc motor actuator 4 quadrant torque speed curve.
71+
torque_speed_pairs of interest:
72+
73+
0 - fully inside torque speed curve and effort limit (quadrant 1)
74+
1 - greater than effort limit but under torque-speed curve (quadrant 1)
75+
2 - greater than effort limit and outside torque-speed curve (quadrant 1)
76+
3 - less than effort limit but outside torque speed curve (quadrant 1)
77+
4 - less than effort limit but outside torque speed curve and outside corner velocity(quadrant 4)
78+
5 - fully inside torque speed curve and effort limit (quadrant 4)
79+
6 - fully outside torque speed curve and -effort limit (quadrant 4)
80+
7 - fully inside torque speed curve, outside -effort limit, and inside corner velocity (quadrant 4)
81+
8 - fully inside torque speed curves, outside -effort limit, and outside corner velocity (quadrant 4)
82+
9 - less than effort limit but outside torque speed curve and inside corner velocity (quadrant 4)
83+
e - effort_limit
84+
s - saturation_effort
85+
v - velocity_limit
86+
c - corner velocity
87+
\ - torque-speed linear boundary between v and s
88+
each torque_speed_point will be tested in quadrant 3 and 4
89+
===========================================================
90+
Torque
91+
\ (+)
92+
\ |
93+
Q2 s Q1
94+
| \ 2
95+
\ | 1 \
96+
c ---------------------e-----\
97+
\ | \
98+
\ | 0 \ 3
99+
\ | \
100+
(-)-----------v -------------o-------------v --------------(+) Speed
101+
\ | \ 9 4
102+
\ | 5 \
103+
\ | \
104+
\ -----e---------------------c
105+
\ | \ 6
106+
Q3 \ | 7 Q4 \
107+
\s \
108+
|\ 8 \
109+
(-) \
110+
============================================================
111+
"""
112+
effort_lim = 60
113+
saturation_effort = 100.0
114+
velocity_limit = 50
115+
116+
torque_speed_pairs = [
117+
(30.0, 10.0), # 0
118+
(70.0, 10.0), # 1
119+
(80.0, 40.0), # 2
120+
(30.0, 40.0), # 3
121+
(-20.0, 90.0), # 4
122+
(-30.0, 10.0), # 5
123+
(-80.0, 110.0), # 6
124+
(-80.0, 50.0), # 7
125+
(-120.0, 90.0), # 8
126+
(-10.0, 70.0), # 9
127+
(-30.0, -10.0), # -0
128+
(-70.0, -10.0), # -1
129+
(-80.0, -40.0), # -2
130+
(-30.0, -40.0), # -3
131+
(20.0, -90.0), # -4
132+
(30.0, -10.0), # -5
133+
(80.0, -110.0), # -6
134+
(80.0, -50.0), # -7
135+
(120.0, -90.0), # -8
136+
(10.0, -70.0), # -9
137+
]
138+
expected_clipped_effort = [
139+
30.0, # 0
140+
60.0, # 1
141+
20.0, # 2
142+
20.0, # 3
143+
-60.0, # 4
144+
-30.0, # 5
145+
-60.0, # 6
146+
-60.0, # 7
147+
-60.0, # 8
148+
-40.0, # 9
149+
-30.0, # -0
150+
-60.0, # -1
151+
-20, # -2
152+
-20, # -3
153+
60.0, # -4
154+
30.0, # -5
155+
60.0, # -6
156+
60.0, # -7
157+
60.0, # -8
158+
40.0, # -9
159+
]
160+
161+
joint_names = [f"joint_{d}" for d in range(num_joints)]
162+
joint_ids = [d for d in range(num_joints)]
163+
stiffness = 200
164+
damping = 10
165+
actuator_cfg = DCMotorCfg(
166+
joint_names_expr=joint_names,
167+
stiffness=stiffness,
168+
damping=damping,
169+
effort_limit=effort_lim,
170+
velocity_limit=velocity_limit,
171+
saturation_effort=saturation_effort,
172+
)
173+
174+
actuator = actuator_cfg.class_type(
175+
actuator_cfg,
176+
joint_names=joint_names,
177+
joint_ids=joint_ids,
178+
num_envs=num_envs,
179+
device=device,
180+
stiffness=actuator_cfg.stiffness,
181+
damping=actuator_cfg.damping,
182+
)
183+
184+
ts = torque_speed_pairs[test_point]
185+
torque = ts[0]
186+
speed = ts[1]
187+
actuator._joint_vel[:] = speed * torch.ones(num_envs, num_joints, device=device)
188+
effort = torque * torch.ones(num_envs, num_joints, device=device)
189+
clipped_effort = actuator._clip_effort(effort)
190+
torch.testing.assert_close(
191+
expected_clipped_effort[test_point] * torch.ones(num_envs, num_joints, device=device),
192+
clipped_effort,
193+
)

0 commit comments

Comments
 (0)