Unverified Commit efabf203 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Adds parsing of joint parameters from USD for actuators (#258)

# Description

Currently, the joint parameters must always be specified from the
user-defined configurations. Setting them to None makes them go to zero
(for stiffness and damping) and infinity (for limits). This is not great
since many assets may have some values in the USD file that they have
tuned using inspection tools in Omniverse.

This MR changes the behavior of `None` in the actuator configuration to
load default values provided as inputs to the actuator class. It also
loads other joint drive parameters such as friction and armature.

## Type of change

- Bug fix (non-breaking change which fixes an issue)
- Breaking change (fix or feature that would cause existing
functionality to not work as expected)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.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
parent 48146c2b
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.9.52"
version = "0.9.53"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.9.53 (2023-11-29)
~~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Changed the behavior of passing :obj:`None` to the :class:`omni.isaac.orbit.actuators.ActuatorBaseCfg`
class. Earlier, they were resolved to fixed default values. Now, they imply that the values are loaded
from the USD joint drive configuration.
Added
^^^^^
* Added setting of joint armature and friction quantities to the articulation class.
0.9.52 (2023-11-29)
~~~~~~~~~~~~~~~~~~~
......
......@@ -21,7 +21,7 @@ class ActuatorBaseCfg:
class_type: type[ActuatorBase] = MISSING
"""The associated actuator class.
The class should inherit from :class:`omni.isaac.orbit.actuators.actuator_base.ActuatorBase`.
The class should inherit from :class:`omni.isaac.orbit.actuators.ActuatorBase`.
"""
joint_names_expr: list[str] = MISSING
......@@ -34,7 +34,7 @@ class ActuatorBaseCfg:
effort_limit: float | None = None
"""Force/Torque limit of the joints in the group. Defaults to :obj:`None`.
If :obj:`None`, the limit is set to infinity.
If :obj:`None`, the limit is set to the value specified in the USD joint prim.
"""
velocity_limit: float | None = None
......@@ -46,13 +46,25 @@ class ActuatorBaseCfg:
stiffness: dict[str, float] | float | None = MISSING
"""Stiffness gains (also known as p-gain) of the joints in the group.
If :obj:`None`, the stiffness is set to 0.
If :obj:`None`, the stiffness is set to the value from the USD joint prim.
"""
damping: dict[str, float] | float | None = MISSING
"""Damping gains (also known as d-gain) of the joints in the group.
If :obj:`None`, the damping is set to 0.
If :obj:`None`, the damping is set to the value from the USD joint prim.
"""
armature: dict[str, float] | float | None = None
"""Armature of the joints in the group.
If :obj:`None`, the armature is set to the value from the USD joint prim.
"""
friction: dict[str, float] | float | None = None
"""Joint friction of the joints in the group.
If :obj:`None`, the joint friction is set to the value from the USD joint prim.
"""
......
......@@ -42,10 +42,8 @@ class ActuatorNetLSTM(DCMotor):
cfg: ActuatorNetLSTMCfg
"""The configuration of the actuator model."""
def __init__(
self, cfg: ActuatorNetLSTMCfg, joint_names: list[str], joint_ids: list[int], num_envs: int, device: str
):
super().__init__(cfg, joint_names, joint_ids, num_envs, device)
def __init__(self, cfg: ActuatorNetLSTMCfg, *args, **kwargs):
super().__init__(cfg, *args, **kwargs)
# load the model from JIT file
file_bytes = read_file(self.cfg.network_file)
......@@ -65,6 +63,10 @@ class ActuatorNetLSTM(DCMotor):
self.sea_hidden_state_per_env = self.sea_hidden_state.view(layer_shape_per_env)
self.sea_cell_state_per_env = self.sea_cell_state.view(layer_shape_per_env)
"""
Operations.
"""
def reset(self, env_ids: Sequence[int]):
# reset the hidden and cell states for the specified environments
with torch.no_grad():
......@@ -119,10 +121,8 @@ class ActuatorNetMLP(DCMotor):
cfg: ActuatorNetMLPCfg
"""The configuration of the actuator model."""
def __init__(
self, cfg: ActuatorNetMLPCfg, joint_names: list[str], joint_ids: list[int], num_envs: int, device: str
):
super().__init__(cfg, joint_names, joint_ids, num_envs, device)
def __init__(self, cfg: ActuatorNetMLPCfg, *args, **kwargs):
super().__init__(cfg, *args, **kwargs)
# load the model from JIT file
file_bytes = read_file(self.cfg.network_file)
......@@ -135,6 +135,10 @@ class ActuatorNetMLP(DCMotor):
)
self._joint_vel_history = torch.zeros(self._num_envs, history_length, self.num_joints, device=self._device)
"""
Operations.
"""
def reset(self, env_ids: Sequence[int]):
# reset the history for the specified environments
self._joint_pos_error_history[env_ids] = 0.0
......
......@@ -176,8 +176,8 @@ class DCMotor(IdealPDActuator):
cfg: DCMotorCfg
"""The configuration for the actuator model."""
def __init__(self, cfg: DCMotorCfg, joint_names: list[str], joint_ids: list[int], num_envs: int, device: str):
super().__init__(cfg, joint_names, joint_ids, num_envs, device)
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
......@@ -185,6 +185,8 @@ class DCMotor(IdealPDActuator):
self._saturation_effort = torch.inf
# prepare joint vel buffer for max effort computation
self._joint_vel = torch.zeros_like(self.computed_effort)
# create buffer for zeros effort
self._zeros_effort = torch.zeros_like(self.computed_effort)
# check that quantities are provided
if self.cfg.velocity_limit is None:
raise ValueError("The velocity limit must be provided for the DC motor actuator model.")
......@@ -209,10 +211,10 @@ class DCMotor(IdealPDActuator):
# compute torque limits
# -- max limit
max_effort = self.cfg.saturation_effort * (1.0 - self._joint_vel / self.velocity_limit)
max_effort = torch.clip(max_effort, min=0.0, max=self.effort_limit)
max_effort = torch.clip(max_effort, min=self._zeros_effort, max=self.effort_limit)
# -- min limit
min_effort = self.cfg.saturation_effort * (-1.0 - self._joint_vel / self.velocity_limit)
min_effort = torch.clip(min_effort, min=-self.effort_limit, max=0.0)
min_effort = torch.clip(min_effort, min=-self.effort_limit, max=self._zeros_effort)
# clip the torques based on the motor limits
return torch.clip(effort, min=min_effort, max=max_effort)
......@@ -49,13 +49,28 @@ class ArticulationData(RigidObjectData):
##
joint_pos_target: torch.Tensor = None
"""Joint position targets provided to simulation. Shape is ``(count, num_joints)``."""
"""Joint position targets commanded by the user. Shape is ``(count, num_joints)``.
For an implicit actuator model, the targets are directly set into the simulation.
For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`),
which are then set into the simulation.
"""
joint_vel_target: torch.Tensor = None
"""Joint velocity targets provided to simulation. Shape is ``(count, num_joints)``."""
"""Joint velocity targets commanded by the user. Shape is ``(count, num_joints)``.
For an implicit actuator model, the targets are directly set into the simulation.
For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`),
which are then set into the simulation.
"""
joint_effort_target: torch.Tensor = None
"""Joint effort targets provided to simulation. Shape is ``(count, num_joints)``."""
"""Joint effort targets commanded by the user. Shape is ``(count, num_joints)``.
For an implicit actuator model, the targets are directly set into the simulation.
For an explicit actuator model, the targets are used to compute the joint torques (see :attr:`applied_torque`),
which are then set into the simulation.
"""
joint_stiffness: torch.Tensor = None
"""Joint stiffness provided to simulation. Shape is ``(count, num_joints)``."""
......@@ -63,20 +78,31 @@ class ArticulationData(RigidObjectData):
joint_damping: torch.Tensor = None
"""Joint damping provided to simulation. Shape is ``(count, num_joints)``."""
joint_armature: torch.Tensor = None
"""Joint armature provided to simulation. Shape is ``(count, num_joints)``."""
joint_friction: torch.Tensor = None
"""Joint friction provided to simulation. Shape is ``(count, num_joints)``."""
##
# Joint commands -- Explicit actuators.
##
computed_torque: torch.Tensor = None
"""Joint torques computed from the actuator model (before clipping).
Shape is ``(count, num_joints)``.
"""Joint torques computed from the actuator model (before clipping). Shape is ``(count, num_joints)``.
This quantity is the raw torque output from the actuator mode, before any clipping is applied.
It is exposed for users who want to inspect the computations inside the actuator model.
For instance, to penalize the learning agent for a difference between the computed and applied torques.
Note: The torques are zero for implicit actuator models.
"""
applied_torque: torch.Tensor = None
"""Joint torques applied from the actuator model (after clipping).
Shape is ``(count, num_joints)``.
"""Joint torques applied from the actuator model (after clipping). Shape is ``(count, num_joints)``.
These torques are set into the simulation, after clipping the :attr:`computed_torque` based on the
actuator model.
Note: The torques are zero for implicit actuator models.
"""
......
......@@ -27,6 +27,7 @@ import carb
import omni.isaac.core.utils.stage as stage_utils
import omni.isaac.orbit.sim as sim_utils
import omni.isaac.orbit.utils.string as string_utils
from omni.isaac.orbit.actuators import ImplicitActuatorCfg
from omni.isaac.orbit.assets import Articulation, ArticulationCfg
from omni.isaac.orbit.assets.config import ANYMAL_C_CFG, FRANKA_PANDA_ARM_WITH_PANDA_HAND_CFG
......@@ -239,6 +240,78 @@ class TestArticulation(unittest.TestCase):
self.assertTrue(robot.data.root_ang_vel_w[0, 2].item() > 0.1)
self.assertTrue(robot.data.root_ang_vel_w[1, 2].item() > 0.1)
def test_loading_gains_from_usd(self):
"""Test that gains are loaded from USD file if actuator model has them as None."""
# Create articulation
robot_cfg = ArticulationCfg(
prim_path="/World/Robot",
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Humanoid/humanoid_instanceable.usd"),
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 1.34)),
actuators={"body": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=None, damping=None)},
)
robot = Articulation(cfg=robot_cfg)
# Play sim
self.sim.reset()
# Expected gains
# -- Stiffness values
expected_stiffness = {
".*_waist.*": 20.0,
".*_upper_arm.*": 10.0,
"pelvis": 10.0,
".*_lower_arm": 2.0,
".*_thigh:0": 10.0,
".*_thigh:1": 20.0,
".*_thigh:2": 10.0,
".*_shin": 5.0,
".*_foot.*": 2.0,
}
indices_list, _, values_list = string_utils.resolve_matching_names_values(expected_stiffness, robot.joint_names)
expected_stiffness = torch.zeros(robot.root_view.count, robot.num_joints, device=robot.device)
expected_stiffness[:, indices_list] = torch.tensor(values_list, device=robot.device)
# -- Damping values
expected_damping = {
".*_waist.*": 5.0,
".*_upper_arm.*": 5.0,
"pelvis": 5.0,
".*_lower_arm": 1.0,
".*_thigh:0": 5.0,
".*_thigh:1": 5.0,
".*_thigh:2": 5.0,
".*_shin": 0.1,
".*_foot.*": 1.0,
}
indices_list, _, values_list = string_utils.resolve_matching_names_values(expected_damping, robot.joint_names)
expected_damping = torch.zeros_like(expected_stiffness)
expected_damping[:, indices_list] = torch.tensor(values_list, device=robot.device)
# Check that gains are loaded from USD file
torch.testing.assert_close(robot.actuators["body"].stiffness, expected_stiffness)
torch.testing.assert_close(robot.actuators["body"].damping, expected_damping)
def test_setting_gains_from_cfg(self):
"""Test that gains are loaded from the configuration correctly."""
# Create articulation
robot_cfg = ArticulationCfg(
prim_path="/World/Robot",
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Humanoid/humanoid_instanceable.usd"),
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 1.34)),
actuators={"body": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=10.0, damping=2.0)},
)
robot = Articulation(cfg=robot_cfg)
# Play sim
self.sim.reset()
# Expected gains
expected_stiffness = torch.full((robot.root_view.count, robot.num_joints), 10.0, device=robot.device)
expected_damping = torch.full_like(expected_stiffness, 2.0)
# Check that gains are loaded from USD file
torch.testing.assert_close(robot.actuators["body"].stiffness, expected_stiffness)
torch.testing.assert_close(robot.actuators["body"].damping, expected_damping)
if __name__ == "__main__":
try:
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment