Skip to content

Fixes DCMotor clipping for negative power and adds actuator tests #2300

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 43 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
43 commits
Select commit Hold shift + click to select a range
1fa5a8a
add implicit actuator init and effort limit test
jtigue-bdai Apr 8, 2025
3b9d9f7
add edge cases and velocity limit cfg tests
jtigue-bdai Apr 8, 2025
97ea7f0
rename to test_implicit_actuator
jtigue-bdai Apr 9, 2025
c1dab1e
cleanup and add ideal_pd tests
jtigue-bdai Apr 9, 2025
cddbeb5
add ideal_pd compute test
jtigue-bdai Apr 9, 2025
283ef5c
dc motor clip test for positive power
jtigue-bdai Apr 10, 2025
ca7b1a0
change log
jtigue-bdai Apr 10, 2025
c6e757f
fix test and clipping
jtigue-bdai Apr 11, 2025
37674e8
update documentation
jtigue-bdai Apr 11, 2025
ba0e4e1
update changelog
jtigue-bdai Apr 11, 2025
3e50893
change axes of ascii torque-speed curve
jtigue-bdai Apr 14, 2025
a96e1d6
sepereate dc motor tests to anothe file
jtigue-bdai May 9, 2025
b6138ae
update dc motor docs
jtigue-bdai May 9, 2025
ee8c3bb
fix test docstring
jtigue-bdai May 9, 2025
38db7a0
Merge branch 'main' into jat/feat/q4_dc_motor_limits
kellyguo11 May 13, 2025
5cce90e
Merge branch 'main' into jat/feat/q4_dc_motor_limits
jtigue-bdai May 14, 2025
91863cb
Merge branch 'main' into jat/feat/q4_dc_motor_limits
kellyguo11 May 15, 2025
03649aa
fix test convertion to pytest
jtigue-bdai May 16, 2025
a62d818
Merge branch 'main' into jat/feat/q4_dc_motor_limits
jtigue-bdai May 16, 2025
4359f0b
fix format
jtigue-bdai May 16, 2025
0299af9
Trigger build
jtigue-bdai May 16, 2025
96f2365
Trigger build
jtigue-bdai May 16, 2025
7cf4b59
Merge branch 'main' into jat/feat/q4_dc_motor_limits
jtigue-bdai May 20, 2025
c104e38
fix clippling for very large input velocities
jtigue-bdai May 19, 2025
e42f04f
fix format
jtigue-bdai May 20, 2025
14e4df3
reduce numerical clamping
jtigue-bdai May 20, 2025
477d25d
Merge branch 'main' into jat/feat/q4_dc_motor_limits
kellyguo11 May 24, 2025
9816be1
Update extension.toml
kellyguo11 May 24, 2025
58740b8
Merge branch 'main' into jat/feat/q4_dc_motor_limits
kellyguo11 May 26, 2025
d207856
add clamp fix to lstm net actuator
jtigue-bdai May 27, 2025
43f7f44
Merge branch 'main' into jat/feat/q4_dc_motor_limits
kellyguo11 May 29, 2025
570537d
add extra dc motor test case
jtigue-bdai Jun 6, 2025
169db35
Merge branch 'main' into jat/feat/q4_dc_motor_limits
jtigue-bdai Jun 27, 2025
94a017f
fix documentation and return lstm actuator to original
jtigue-bdai Jun 6, 2025
e434e46
adjust benchmaring configs for testing
jtigue-bdai Jun 13, 2025
228a2d9
clean up format
jtigue-bdai Jun 27, 2025
a2620c3
Fix license
jtigue-bdai Jun 27, 2025
55cfedf
Revert actuator_net clip change
jtigue-bdai Jun 27, 2025
9db87eb
format
jtigue-bdai Jun 27, 2025
1da335c
Format
jtigue-bdai Jun 27, 2025
0d5ddd2
add velocity limitation to lstmActuatorNet
jtigue-bdai Jun 27, 2025
d0eac46
Trigger Build
jtigue-bdai Jun 27, 2025
4b67629
reset benchmark configs
jtigue-bdai Jun 27, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
5 changes: 5 additions & 0 deletions docs/source/api/lab/isaaclab.actuators.rst
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,11 @@ Ideal PD Actuator
DC Motor Actuator
-----------------

.. figure:: ../../../_static/overview/actuator-group/dc_motor_clipping.jpg
:align: center
:figwidth: 100%
:alt: The effort clipping as a function of joint velocity for a linear DC Motor.

.. autoclass:: DCMotor
:members:
:inherited-members:
Expand Down
2 changes: 1 addition & 1 deletion source/isaaclab/config/extension.toml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
[package]

# Note: Semantic Versioning is used: https://semver.org/
version = "0.40.10"
version = "0.40.11"

# Description
title = "Isaac Lab framework for Robot Learning"
Expand Down
16 changes: 16 additions & 0 deletions source/isaaclab/docs/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,22 @@
Changelog
---------

0.40.11 (2025-05-20)
~~~~~~~~~~~~~~~~~~~~

Added
^^^^^

* Added unit tests for :class:`~isaaclab.actuator.ImplicitActuator`, :class:`~isaaclab.actuator.IdealPDActuator`,
and :class:`~isaaclab.actuator.DCMotor` independent of :class:`~isaaclab.assets.Articulation`

Changed
^^^^^^^

* Changed the way clipping is handled for :class:`~isaaclab.actuator.DCMotor` for torque-speed points in when in
negative power regions.


0.40.10 (2025-06-25)
~~~~~~~~~~~~~~~~~~~~

Expand Down
2 changes: 1 addition & 1 deletion source/isaaclab/isaaclab/actuators/actuator_net.py
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ def compute(
self.sea_input[:, 0, 0] = (control_action.joint_positions - joint_pos).flatten()
self.sea_input[:, 0, 1] = joint_vel.flatten()
# save current joint vel for dc-motor clipping
self._joint_vel[:] = joint_vel
self._joint_vel[:] = torch.clip(joint_vel, min=-self.velocity_limit, max=self.velocity_limit)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We will need to somehow verify our sim-to-real for the robots if all these changes happen. Even if they do make sense mathematically, they may affect downstream sim-to-real pipelines unknowingly.

Is there a way to verify this on our side first before rolling it out to the public?


# run network inference
with torch.inference_mode():
Expand Down
68 changes: 46 additions & 22 deletions source/isaaclab/isaaclab/actuators/actuator_pd.py
Original file line number Diff line number Diff line change
Expand Up @@ -201,8 +201,8 @@ def compute(
class DCMotor(IdealPDActuator):
r"""Direct control (DC) motor actuator model with velocity-based saturation model.

It uses the same model as the :class:`IdealActuator` for computing the torques from input commands.
However, it implements a saturation model defined by DC motor characteristics.
It uses the same model as the :class:`IdealPDActuator` for computing the torques from input commands.
However, it implements a saturation model defined by a linear four quadrant DC motor torque-speed curve.

A DC motor is a type of electric motor that is powered by direct current electricity. In most cases,
the motor is connected to a constant source of voltage supply, and the current is controlled by a rheostat.
Expand All @@ -211,23 +211,28 @@ class DCMotor(IdealPDActuator):

A DC motor characteristics are defined by the following parameters:

* Continuous-rated speed (:math:`\dot{q}_{motor, max}`) : The maximum-rated speed of the motor.
* Continuous-stall torque (:math:`\tau_{motor, max}`): The maximum-rated torque produced at 0 speed.
* Saturation torque (:math:`\tau_{motor, sat}`): The maximum torque that can be outputted for a short period.
* No-load speed (:math:`\dot{q}_{motor, max}`) : The maximum-rated speed of the motor at 0 Torque (:attr:`velocity_limit`).
* Stall torque (:math:`\tau_{motor, stall}`): The maximum-rated torque produced at 0 speed (:attr:`saturation_effort`).
* Continuous torque (:math:`\tau_{motor, con}`): The maximum torque that can be outputted for a short period. This
is often enforced on the current drives for a DC motor to limit overheating, prevent mechanical damage, or
enforced by electrical limitations.(:attr:`effort_limit`).
* Corner velocity (:math:`V_{c}`): The velocity where the torque-speed curve intersects with continuous torque.

Based on these parameters, the instantaneous minimum and maximum torques are defined as follows:
Based on these parameters, the instantaneous minimum and maximum torques for velocities between corner velocities
(where torque-speed curve intersects with continuous torque) are defined as follows:

.. math::

\tau_{j, max}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left(1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right), 0.0, \tau_{j, max} \right) \\
\tau_{j, min}(\dot{q}) & = clip \left (\tau_{j, sat} \times \left( -1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right), - \tau_{j, max}, 0.0 \right)

\tau_{j, max}(\dot{q}) & = clip \left (\tau_{j, stall} \times \left(1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right), -∞, \tau_{j, con} \right) \\
\tau_{j, min}(\dot{q}) & = clip \left (\tau_{j, stall} \times \left( -1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right), - \tau_{j, con}, ∞ \right)

where :math:`\gamma` is the gear ratio of the gear box connecting the motor and the actuated joint ends,
:math:`\dot{q}_{j, max} = \gamma^{-1} \times \dot{q}_{motor, max}`, :math:`\tau_{j, max} =
\gamma \times \tau_{motor, max}` and :math:`\tau_{j, peak} = \gamma \times \tau_{motor, peak}`
are the maximum joint velocity, maximum joint torque and peak torque, respectively. These parameters
:math:`\dot{q}_{j, max} = \gamma^{-1} \times \dot{q}_{motor, max}`, :math:`\tau_{j, con} =
\gamma \times \tau_{motor, con}` and :math:`\tau_{j, stall} = \gamma \times \tau_{motor, stall}`
are the maximum joint velocity, continuous joint torque and stall torque, respectively. These parameters
are read from the configuration instance passed to the class.

Using these values, the computed torques are clipped to the minimum and maximum values based on the
Expand All @@ -237,6 +242,18 @@ class DCMotor(IdealPDActuator):

\tau_{j, applied} = clip(\tau_{computed}, \tau_{j, min}(\dot{q}), \tau_{j, max}(\dot{q}))

If the velocity of the joint is outside corner velocities (this would be due to external forces) the
applied output torque will be driven to the torque speed curve providing braking torque that will try to drive the
motor down to the corner velocities

.. math::

if \quad & \dot{q}>V_{c} \quad & then \quad & \tau_{j, applied} = \tau_{j, stall} \times \left(1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right) \\
if \quad & \dot{q}<-V_{c} \quad & then \quad & \tau_{j, applied} = \tau_{j, stall} \times \left(-1 -
\frac{\dot{q}}{\dot{q}_{j, max}}\right)

The figure below demonstrates the clipping action for example (velocity, torque) pairs.
"""

cfg: DCMotorCfg
Expand All @@ -245,10 +262,11 @@ class DCMotor(IdealPDActuator):
def __init__(self, cfg: DCMotorCfg, *args, **kwargs):
super().__init__(cfg, *args, **kwargs)
# parse configuration
if self.cfg.saturation_effort is not None:
self._saturation_effort = self.cfg.saturation_effort
else:
self._saturation_effort = torch.inf
if self.cfg.saturation_effort is None:
raise ValueError("The saturation_effort must be provided for the DC motor actuator model.")
self._saturation_effort = self.cfg.saturation_effort
# find the velocity on the torque-speed curve that intersects effort_limit in the second and fourth quadrant
self._vel_at_effort_lim = self.velocity_limit * (1 + self.effort_limit / self._saturation_effort)
# prepare joint vel buffer for max effort computation
self._joint_vel = torch.zeros_like(self.computed_effort)
# create buffer for zeros effort
Expand All @@ -275,15 +293,21 @@ def compute(

def _clip_effort(self, effort: torch.Tensor) -> torch.Tensor:
# compute torque limits
torque_speed_top = self._saturation_effort * (1.0 - self._joint_vel / self.velocity_limit)
torque_speed_bottom = self._saturation_effort * (-1.0 - self._joint_vel / self.velocity_limit)
# -- max limit
max_effort = self._saturation_effort * (1.0 - self._joint_vel / self.velocity_limit)
max_effort = torch.clip(max_effort, min=self._zeros_effort, max=self.effort_limit)
max_effort = torch.clip(torque_speed_top, max=self.effort_limit)
# -- min limit
min_effort = self._saturation_effort * (-1.0 - self._joint_vel / self.velocity_limit)
min_effort = torch.clip(min_effort, min=-self.effort_limit, max=self._zeros_effort)
min_effort = torch.clip(torque_speed_bottom, min=-self.effort_limit)

# clip the torques based on the motor limits
return torch.clip(effort, min=min_effort, max=max_effort)
clamped = torch.clip(effort, min=min_effort, max=max_effort)
gt_vel_at_effort_lim = self._joint_vel > self._vel_at_effort_lim
lt_vel_at_neg_effort_lim = self._joint_vel < -self._vel_at_effort_lim
clamped[gt_vel_at_effort_lim] = torque_speed_top[gt_vel_at_effort_lim]
clamped[lt_vel_at_neg_effort_lim] = torque_speed_bottom[lt_vel_at_neg_effort_lim]
Comment on lines +305 to +308
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think we need to do recomputation here since (torque_speed_bottom, torque_speed_top) shouldn't lie outside (-effort_limit, effort_limit) for cases where velocity is higher than the actual velocity limits.

Maybe I misunderstand a bit, but shouldn't just the clipping once be sufficient?

Copy link
Collaborator Author

@jtigue-bdai jtigue-bdai Jun 4, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what this handles is the event that the joint if forced to higher velocities from outside forces like gravity when landing after a jump. A motor will provide resistivity torque regardless of an "Effort limit". It may damage circuits, motors, or mechanical components when it does it but the actuator will try to resist.

It a pretty specific use case so i could see having this be configurable if people want to model that.

It is likely a cause of the issues I am seeing with the Anymal-C LSTM net actuators in benchmarking.


return clamped


class DelayedPDActuator(IdealPDActuator):
Expand Down
197 changes: 197 additions & 0 deletions source/isaaclab/test/actuators/test_dc_motor.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,197 @@
# Copyright (c) 2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

from isaaclab.app import AppLauncher

HEADLESS = True

# if not AppLauncher.instance():
simulation_app = AppLauncher(headless=HEADLESS).app

"""Rest of imports follows"""

import torch

import pytest

from isaaclab.actuators import DCMotorCfg


@pytest.mark.parametrize("num_envs", [1, 2])
@pytest.mark.parametrize("num_joints", [1, 2])
@pytest.mark.parametrize("device", ["cuda:0", "cpu"])
def test_dc_motor_init_minimum(num_envs, num_joints, device):
joint_names = [f"joint_{d}" for d in range(num_joints)]
joint_ids = [d for d in range(num_joints)]
stiffness = 200
damping = 10
effort_limit = 60.0
saturation_effort = 100.0
velocity_limit = 50

actuator_cfg = DCMotorCfg(
joint_names_expr=joint_names,
stiffness=stiffness,
damping=damping,
effort_limit=effort_limit,
saturation_effort=saturation_effort,
velocity_limit=velocity_limit,
)
# assume Articulation class:
# - finds joints (names and ids) associate with the provided joint_names_expr

actuator = actuator_cfg.class_type(
actuator_cfg,
joint_names=joint_names,
joint_ids=joint_ids,
num_envs=num_envs,
device=device,
)

# check device and shape
torch.testing.assert_close(actuator.computed_effort, torch.zeros(num_envs, num_joints, device=device))
torch.testing.assert_close(actuator.applied_effort, torch.zeros(num_envs, num_joints, device=device))
torch.testing.assert_close(
actuator.effort_limit,
effort_limit * torch.ones(num_envs, num_joints, device=device),
)
torch.testing.assert_close(
actuator.velocity_limit, velocity_limit * torch.ones(num_envs, num_joints, device=device)
)


@pytest.mark.parametrize("num_envs", [1, 2])
@pytest.mark.parametrize("num_joints", [1, 2])
@pytest.mark.parametrize("device", ["cuda", "cpu"])
@pytest.mark.parametrize("test_point", range(20))
def test_dc_motor_clip(num_envs, num_joints, device, test_point):
r"""Test the computation of the dc motor actuator 4 quadrant torque speed curve.
torque_speed_pairs of interest:

0 - fully inside torque speed curve and effort limit (quadrant 1)
1 - greater than effort limit but under torque-speed curve (quadrant 1)
2 - greater than effort limit and outside torque-speed curve (quadrant 1)
3 - less than effort limit but outside torque speed curve (quadrant 1)
4 - less than effort limit but outside torque speed curve and outside corner velocity(quadrant 4)
5 - fully inside torque speed curve and effort limit (quadrant 4)
6 - fully outside torque speed curve and -effort limit (quadrant 4)
7 - fully inside torque speed curve, outside -effort limit, and inside corner velocity (quadrant 4)
8 - fully inside torque speed curves, outside -effort limit, and outside corner velocity (quadrant 4)
9 - less than effort limit but outside torque speed curve and inside corner velocity (quadrant 4)
e - effort_limit
s - saturation_effort
v - velocity_limit
c - corner velocity
\ - torque-speed linear boundary between v and s
each torque_speed_point will be tested in quadrant 3 and 4
===========================================================
Torque
\ (+)
\ |
Q2 s Q1
| \ 2
\ | 1 \
c ---------------------e-----\
\ | \
\ | 0 \ 3
\ | \
(-)-----------v -------------o-------------v --------------(+) Speed
\ | \ 9 4
\ | 5 \
\ | \
\ -----e---------------------c
\ | \ 6
Q3 \ | 7 Q4 \
\s \
|\ 8 \
(-) \
============================================================
"""
effort_lim = 60
saturation_effort = 100.0
velocity_limit = 50

torque_speed_pairs = [
(30.0, 10.0), # 0
(70.0, 10.0), # 1
(80.0, 40.0), # 2
(30.0, 40.0), # 3
(-20.0, 90.0), # 4
(-30.0, 10.0), # 5
(-80.0, 110.0), # 6
(-80.0, 50.0), # 7
(-120.0, 90.0), # 8
(-10.0, 70.0), # 9
(-30.0, -10.0), # -0
(-70.0, -10.0), # -1
(-80.0, -40.0), # -2
(-30.0, -40.0), # -3
(20.0, -90.0), # -4
(30.0, -10.0), # -5
(80.0, -110.0), # -6
(80.0, -50.0), # -7
(120.0, -90.0), # -8
(10.0, -70.0), # -9
]
expected_clipped_effort = [
30.0,
60.0,
20.0,
20.0,
-80.0,
-30.0,
-120.0,
-60.0,
-80.0,
-40.0,
-30.0,
-60.0,
-20,
-20,
80.0,
30.0,
120.0,
60.0,
80.0,
40.0,
]

joint_names = [f"joint_{d}" for d in range(num_joints)]
joint_ids = [d for d in range(num_joints)]
stiffness = 200
damping = 10
effort_lim = 60
saturation_effort = 100.0
velocity_limit = 50
actuator_cfg = DCMotorCfg(
joint_names_expr=joint_names,
stiffness=stiffness,
damping=damping,
effort_limit=effort_lim,
velocity_limit=velocity_limit,
saturation_effort=saturation_effort,
)

actuator = actuator_cfg.class_type(
actuator_cfg,
joint_names=joint_names,
joint_ids=joint_ids,
num_envs=num_envs,
device=device,
stiffness=actuator_cfg.stiffness,
damping=actuator_cfg.damping,
)

ts = torque_speed_pairs[test_point]
torque = ts[0]
speed = ts[1]
actuator._joint_vel[:] = speed * torch.ones(num_envs, num_joints, device=device)
effort = torque * torch.ones(num_envs, num_joints, device=device)
clipped_effort = actuator._clip_effort(effort)

torch.testing.assert_close(
expected_clipped_effort[test_point] * torch.ones(num_envs, num_joints, device=device),
clipped_effort,
)
Loading