-
Notifications
You must be signed in to change notification settings - Fork 2k
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
base: main
Are you sure you want to change the base?
Changes from all commits
1fa5a8a
3b9d9f7
97ea7f0
c1dab1e
cddbeb5
283ef5c
ca7b1a0
c6e757f
37674e8
ba0e4e1
3e50893
a96e1d6
b6138ae
ee8c3bb
38db7a0
5cce90e
91863cb
03649aa
a62d818
4359f0b
0299af9
96f2365
7cf4b59
c104e38
e42f04f
14e4df3
477d25d
9816be1
58740b8
d207856
43f7f44
570537d
169db35
94a017f
e434e46
228a2d9
a2620c3
55cfedf
9db87eb
1da335c
0d5ddd2
d0eac46
4b67629
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -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. | ||
|
@@ -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 | ||
|
@@ -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 | ||
|
@@ -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 | ||
|
@@ -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
There was a problem hiding this comment. Choose a reason for hiding this commentThe 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? There was a problem hiding this comment. Choose a reason for hiding this commentThe 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): | ||
|
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, | ||
) |
There was a problem hiding this comment.
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?