diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index 7874783cea5..739a464c6a9 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -35,6 +35,7 @@ Guidelines for modifications: * Pascal Roth * Sheikh Dawood * Ossama Ahmed +* Brian McCann ## Contributors diff --git a/docs/source/api/lab/isaaclab.actuators.rst b/docs/source/api/lab/isaaclab.actuators.rst index 5ab005de5b3..fc6cb68018d 100644 --- a/docs/source/api/lab/isaaclab.actuators.rst +++ b/docs/source/api/lab/isaaclab.actuators.rst @@ -32,6 +32,7 @@ Actuator Base :inherited-members: .. autoclass:: ActuatorBaseCfg + :noindex: :members: :inherited-members: :exclude-members: __init__, class_type @@ -45,6 +46,7 @@ Implicit Actuator :show-inheritance: .. autoclass:: ImplicitActuatorCfg + :noindex: :members: :inherited-members: :show-inheritance: @@ -59,6 +61,7 @@ Ideal PD Actuator :show-inheritance: .. autoclass:: IdealPDActuatorCfg + :noindex: :members: :inherited-members: :show-inheritance: @@ -73,6 +76,7 @@ DC Motor Actuator :show-inheritance: .. autoclass:: DCMotorCfg + :noindex: :members: :inherited-members: :show-inheritance: @@ -87,6 +91,7 @@ Delayed PD Actuator :show-inheritance: .. autoclass:: DelayedPDActuatorCfg + :noindex: :members: :inherited-members: :show-inheritance: @@ -101,6 +106,7 @@ Remotized PD Actuator :show-inheritance: .. autoclass:: RemotizedPDActuatorCfg + :noindex: :members: :inherited-members: :show-inheritance: @@ -115,6 +121,7 @@ MLP Network Actuator :show-inheritance: .. autoclass:: ActuatorNetMLPCfg + :noindex: :members: :inherited-members: :show-inheritance: @@ -129,6 +136,7 @@ LSTM Network Actuator :show-inheritance: .. autoclass:: ActuatorNetLSTMCfg + :noindex: :members: :inherited-members: :show-inheritance: diff --git a/scripts/get_omni_version.py b/scripts/get_omni_version.py new file mode 100644 index 00000000000..7ff22c77ffc --- /dev/null +++ b/scripts/get_omni_version.py @@ -0,0 +1,15 @@ +# Copyright (c) 2022-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 + +import omni.kit.app + +from isaaclab.app import AppLauncher + +app_launcher = AppLauncher(headless=True, enable_cameras=True) +simulation_app = app_launcher.app + +app = omni.kit.app.get_app() +kit_version = app.get_kit_version() +print(kit_version) diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 007872f1b52..d3f7315af7d 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.47.7" +version = "0.49.7" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index bbb5f216c81..6c52a859c39 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,18 @@ Changelog --------- +0.49.7 (2025-11-4) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^^^ + +* Implemented drive model improvements for implicit actuators allowing them to configure a new feature within physx to apply + constraints on actuator effort dependent on the torque and velocity on the articulation. +* Reorg some configuration files to avoid circular dependencies in actuator configuration. +* Introduced a NamedTuple config classes as a way to organize related parameters, and extended the configuration parsing to + work with related (mutually dependent) parameters in the configurations. + 0.47.7 (2025-10-31) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/actuators/__init__.py b/source/isaaclab/isaaclab/actuators/__init__.py index 5ccf5d7b082..2e9f5e05c71 100644 --- a/source/isaaclab/isaaclab/actuators/__init__.py +++ b/source/isaaclab/isaaclab/actuators/__init__.py @@ -23,15 +23,14 @@ """ from .actuator_base import ActuatorBase -from .actuator_cfg import ( - ActuatorBaseCfg, - ActuatorNetLSTMCfg, - ActuatorNetMLPCfg, +from .actuator_base_cfg import ActuatorBaseCfg +from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP +from .actuator_net_cfg import ActuatorNetLSTMCfg, ActuatorNetMLPCfg +from .actuator_pd import DCMotor, DelayedPDActuator, IdealPDActuator, ImplicitActuator, RemotizedPDActuator +from .actuator_pd_cfg import ( DCMotorCfg, DelayedPDActuatorCfg, IdealPDActuatorCfg, ImplicitActuatorCfg, RemotizedPDActuatorCfg, ) -from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP -from .actuator_pd import DCMotor, DelayedPDActuator, IdealPDActuator, ImplicitActuator, RemotizedPDActuator diff --git a/source/isaaclab/isaaclab/actuators/actuator_base.py b/source/isaaclab/isaaclab/actuators/actuator_base.py index 16f04b30b69..348add22bd2 100644 --- a/source/isaaclab/isaaclab/actuators/actuator_base.py +++ b/source/isaaclab/isaaclab/actuators/actuator_base.py @@ -8,13 +8,12 @@ import torch from abc import ABC, abstractmethod from collections.abc import Sequence -from typing import TYPE_CHECKING, ClassVar +from typing import ClassVar import isaaclab.utils.string as string_utils from isaaclab.utils.types import ArticulationActions -if TYPE_CHECKING: - from .actuator_cfg import ActuatorBaseCfg +from .actuator_base_cfg import ActuatorBaseCfg class ActuatorBase(ABC): @@ -76,6 +75,18 @@ class ActuatorBase(ABC): For implicit actuators, the :attr:`velocity_limit` and :attr:`velocity_limit_sim` are the same. """ + drive_model: torch.Tensor + """Three parameters for each joint/env defining the: + (1) [:,:,0] speed_effort_gradient : float = 1 (default), + (2) [:,:,1] maximum_actuator_velocity : float = torch.inf (default), and + (3) [:,:,2] velocity_dependent_resistance : float = 1 (default) + + which define velocity and effort dependent constraints on the motor's performance. + + This feature is only implemented in IsaacSim v5.0. + + The shape is (num_envs, num_joints, 3).""" + stiffness: torch.Tensor """The stiffness (P gain) of the PD controller. Shape is (num_envs, num_joints).""" @@ -116,6 +127,7 @@ def __init__( viscous_friction: torch.Tensor | float = 0.0, effort_limit: torch.Tensor | float = torch.inf, velocity_limit: torch.Tensor | float = torch.inf, + drive_model: torch.Tensor | tuple[float, float, float] = ActuatorBaseCfg.DriveModelCfg(), ): """Initialize the actuator. @@ -149,6 +161,9 @@ def __init__( If a tensor, then the shape is (num_envs, num_joints). velocity_limit: The default velocity limit. Defaults to infinity. If a tensor, then the shape is (num_envs, num_joints). + drive_model: Drive model for the actuator including speed_effort_gradient, max_actuator_velocity, and + velocity_dependent_resistance in that order. Defaults to (0.0, torch.inf, 0.0). + If a tensor then the shape is (num_envs, num_joints, 3). """ # save parameters self.cfg = cfg @@ -176,27 +191,44 @@ def __init__( ("friction", friction), ("dynamic_friction", dynamic_friction), ("viscous_friction", viscous_friction), + ("drive_model", drive_model, 3), ] - for param_name, usd_val in to_check: + for param_name, usd_val, *tuple_len in to_check: + # check if the parameter requires a tuple or a single float + if len(tuple_len) > 0: + shape = (self._num_envs, self.num_joints, tuple_len[0]) + else: + shape = (self._num_envs, self.num_joints) + cfg_val = getattr(self.cfg, param_name) - setattr(self, param_name, self._parse_joint_parameter(cfg_val, usd_val)) + setattr(self, param_name, self._parse_joint_parameter(cfg_val, usd_val, shape, param_name=param_name)) new_val = getattr(self, param_name) allclose = ( - torch.all(new_val == usd_val) if isinstance(usd_val, (float, int)) else torch.allclose(new_val, usd_val) + torch.all(new_val == usd_val) + if isinstance(usd_val, (float, int)) + else ( + all([torch.all(new_val[:, :, i] == float(v)) for i, v in enumerate(usd_val)]) + if isinstance(usd_val, tuple) + else torch.allclose(new_val, usd_val) + ) ) if cfg_val is None or not allclose: self._record_actuator_resolution( cfg_val=getattr(self.cfg, param_name), - new_val=new_val[0], # new val always has the shape of (num_envs, num_joints) + new_val=new_val[0], usd_val=usd_val, joint_names=joint_names, joint_ids=joint_ids, actuator_param=param_name, ) - self.velocity_limit = self._parse_joint_parameter(self.cfg.velocity_limit, self.velocity_limit_sim) - self.effort_limit = self._parse_joint_parameter(self.cfg.effort_limit, self.effort_limit_sim) + self.velocity_limit = self._parse_joint_parameter( + self.cfg.velocity_limit, self.velocity_limit_sim, param_name="velocity_limit" + ) + self.effort_limit = self._parse_joint_parameter( + self.cfg.effort_limit, self.effort_limit_sim, param_name="effort_limit" + ) # create commands buffers for allocation self.computed_effort = torch.zeros(self._num_envs, self.num_joints, device=self._device) @@ -287,13 +319,24 @@ def _record_actuator_resolution(self, cfg_val, new_val, usd_val, joint_names, jo ids = joint_ids if isinstance(joint_ids, torch.Tensor) else list(range(len(joint_names))) for idx, name in enumerate(joint_names): - cfg_val_log = "Not Specified" if cfg_val is None else float(new_val[idx]) - default_usd_val = usd_val if isinstance(usd_val, (float, int)) else float(usd_val[0][idx]) - applied_val_log = default_usd_val if cfg_val is None else float(new_val[idx]) - table.append([name, int(ids[idx]), default_usd_val, cfg_val_log, applied_val_log]) + if len(new_val.shape) == 1: + cfg_val_log = "Not Specified" if cfg_val is None else float(new_val[idx]) + default_usd_val = usd_val if isinstance(usd_val, (float, int)) else float(usd_val[0][idx]) + applied_val_log = default_usd_val if cfg_val is None else float(new_val[idx]) + table.append([name, int(ids[idx]), default_usd_val, cfg_val_log, applied_val_log]) + else: + cfg_val_log = "Not Specified" if cfg_val is None else tuple(new_val[idx]) + default_usd_val = usd_val if isinstance(usd_val, (tuple)) else tuple(usd_val[0][idx][:]) + applied_val_log = default_usd_val if cfg_val is None else tuple(new_val[idx]) + table.append([name, int(ids[idx]), default_usd_val, cfg_val_log, applied_val_log]) def _parse_joint_parameter( - self, cfg_value: float | dict[str, float] | None, default_value: float | torch.Tensor | None + self, + cfg_value: tuple[float, ...] | dict[str, tuple[float, ...]] | float | dict[str, float] | None, + default_value: tuple[float, ...] | float | torch.Tensor | None, + expected_shape: tuple[int, ...] | None = None, + *, + param_name: str = "No name specified", ) -> torch.Tensor: """Parse the joint parameter from the configuration. @@ -301,6 +344,10 @@ def _parse_joint_parameter( cfg_value: The parameter value from the configuration. If None, then use the default value. default_value: The default value to use if the parameter is None. If it is also None, then an error is raised. + expected_shape: The expected shape for the tensor buffer. Usually defaults to (num_envs, num_joints). + + Kwargs: + param_name: a string with the parameter name. (Optional used only in exception messages). Returns: The parsed parameter value. @@ -309,38 +356,87 @@ def _parse_joint_parameter( TypeError: If the parameter value is not of the expected type. TypeError: If the default value is not of the expected type. ValueError: If the parameter value is None and no default value is provided. - ValueError: If the default value tensor is the wrong shape. + ValueError: If a tensor or tuple is the wrong shape. """ + if expected_shape is None: + expected_shape = (self._num_envs, self.num_joints) # create parameter buffer - param = torch.zeros(self._num_envs, self.num_joints, device=self._device) + param = torch.zeros(*expected_shape, device=self._device) + # parse the parameter if cfg_value is not None: if isinstance(cfg_value, (float, int)): # if float, then use the same value for all joints param[:] = float(cfg_value) + elif isinstance(cfg_value, tuple): + # if tuple, ensure we expect a tuple for this parameter + if len(expected_shape) < 3: + raise TypeError( + f"Invalid type for parameter value: {type(cfg_value)} for parameter {param_name}" + + f"actuator on joints {self.joint_names}. Expected float or dict, got tuple" + ) + # ensure the tuple is the correct length, and assign to the last tensor dimensions across all joints + if not len(cfg_value) == expected_shape[2]: + raise ValueError( + f"Invalid tuple length for parameter {param_name}, got {len(cfg_value)}, expected" + + f" {expected_shape[2]}" + ) + for i, v in enumerate(cfg_value): + param[:, :, i] = float(v) elif isinstance(cfg_value, dict): # if dict, then parse the regular expression - indices, _, values = string_utils.resolve_matching_names_values(cfg_value, self.joint_names) - # note: need to specify type to be safe (e.g. values are ints, but we want floats) - param[:, indices] = torch.tensor(values, dtype=torch.float, device=self._device) + indices, j, values = string_utils.resolve_matching_names_values(cfg_value, self.joint_names) + # if the expected shape has two dimensions, we expect floats + if len(expected_shape) < 3: + # note: need to specify type to be safe (e.g. values are ints, but we want floats) + param[:, indices] = torch.tensor(values, dtype=torch.float, device=self._device) + # otherwise, we expect tuples + else: + # We can't directly assign tuples to tensors, so iterate through them + for i, v in enumerate(values): + # Raise an exception if the tuple is the incorrect length + if len(v) != expected_shape[2]: + raise ValueError( + f"Invalid tuple length for parameter {param_name} on joint {j[i]} at index" + f" {indices[i]}," + + f" expected {expected_shape[2]} got {len(v)}." + ) + # Otherwise iterate through the tuple, and assign the values in order. + for i2, v2 in enumerate(v): + param[:, indices[i], i2] = float(v2) else: raise TypeError( f"Invalid type for parameter value: {type(cfg_value)} for " - + f"actuator on joints {self.joint_names}. Expected float or dict." + + f"actuator on joints {self.joint_names}. Expected tuple, float or dict." ) elif default_value is not None: if isinstance(default_value, (float, int)): # if float, then use the same value for all joints param[:] = float(default_value) + elif isinstance(default_value, tuple): + # if tuple, ensure we expect a tuple for this parameter + if len(expected_shape) < 3: + raise TypeError( + f"Invalid default type for parameter value: {type(default_value)} for " + + f"actuator on joints {self.joint_names}. Expected float or dict, got tuple" + ) + # ensure the tuple is the correct length, and assign to the last tensor dimensions across all joints + if not len(default_value) is expected_shape[2]: + raise ValueError( + f"Invalid tuple length for parameter {param_name}, got {len(default_value)}, expected" + + f" {expected_shape[2]}" + ) + for i, v in enumerate(default_value): + param[:, :, i] = float(v) elif isinstance(default_value, torch.Tensor): # if tensor, then use the same tensor for all joints - if default_value.shape == (self._num_envs, self.num_joints): + if tuple(default_value.shape) == expected_shape: param = default_value.float() else: raise ValueError( "Invalid default value tensor shape.\n" - f"Got: {default_value.shape}\n" - f"Expected: {(self._num_envs, self.num_joints)}" + + f"Got: {tuple(default_value.shape)}\n" + + f"Expected: {expected_shape}" ) else: raise TypeError( diff --git a/source/isaaclab/isaaclab/actuators/actuator_cfg.py b/source/isaaclab/isaaclab/actuators/actuator_base_cfg.py similarity index 66% rename from source/isaaclab/isaaclab/actuators/actuator_cfg.py rename to source/isaaclab/isaaclab/actuators/actuator_base_cfg.py index bc2e1a6667d..1813a6dc97e 100644 --- a/source/isaaclab/isaaclab/actuators/actuator_cfg.py +++ b/source/isaaclab/isaaclab/actuators/actuator_base_cfg.py @@ -3,21 +3,18 @@ # # SPDX-License-Identifier: BSD-3-Clause -from collections.abc import Iterable from dataclasses import MISSING -from typing import Literal +from torch import inf +from typing import NamedTuple from isaaclab.utils import configclass -from . import actuator_net, actuator_pd -from .actuator_base import ActuatorBase - @configclass class ActuatorBaseCfg: """Configuration for default actuators in an articulation.""" - class_type: type[ActuatorBase] = MISSING + class_type: type = MISSING """The associated actuator class. The class should inherit from :class:`isaaclab.actuators.ActuatorBase`. @@ -53,6 +50,18 @@ class ActuatorBaseCfg: """ + """Optional (min v5) settings to the drive model capturing performance envelope velocity-effort dependence. + + See: https://docs.omniverse.nvidia.com/kit/docs/omni_physics/107.3/_downloads/f44e831b7f29e7c2ec8e3f2c54418430/drivePerformanceEnvelope.pdf + """ + + class DriveModelCfg(NamedTuple): + speed_effort_gradient: float = 0.0 + max_actuator_velocity: float = inf + velocity_dependent_resistance: float = 0.0 + + drive_model: dict[str, DriveModelCfg] | DriveModelCfg | None = None + velocity_limit: dict[str, float] | float | None = None """Velocity limit of the joints in the group. Defaults to None. @@ -168,124 +177,3 @@ class ActuatorBaseCfg: viscous_friction: dict[str, float] | float | None = None """The viscous friction coefficient of the joints in the group. Defaults to None. """ - - -""" -Implicit Actuator Models. -""" - - -@configclass -class ImplicitActuatorCfg(ActuatorBaseCfg): - """Configuration for an implicit actuator. - - Note: - The PD control is handled implicitly by the simulation. - """ - - class_type: type = actuator_pd.ImplicitActuator - - -""" -Explicit Actuator Models. -""" - - -@configclass -class IdealPDActuatorCfg(ActuatorBaseCfg): - """Configuration for an ideal PD actuator.""" - - class_type: type = actuator_pd.IdealPDActuator - - -@configclass -class DCMotorCfg(IdealPDActuatorCfg): - """Configuration for direct control (DC) motor actuator model.""" - - class_type: type = actuator_pd.DCMotor - - saturation_effort: float = MISSING - """Peak motor force/torque of the electric DC motor (in N-m).""" - - -@configclass -class ActuatorNetLSTMCfg(DCMotorCfg): - """Configuration for LSTM-based actuator model.""" - - class_type: type = actuator_net.ActuatorNetLSTM - # we don't use stiffness and damping for actuator net - stiffness = None - damping = None - - network_file: str = MISSING - """Path to the file containing network weights.""" - - -@configclass -class ActuatorNetMLPCfg(DCMotorCfg): - """Configuration for MLP-based actuator model.""" - - class_type: type = actuator_net.ActuatorNetMLP - # we don't use stiffness and damping for actuator net - stiffness = None - damping = None - - network_file: str = MISSING - """Path to the file containing network weights.""" - - pos_scale: float = MISSING - """Scaling of the joint position errors input to the network.""" - vel_scale: float = MISSING - """Scaling of the joint velocities input to the network.""" - torque_scale: float = MISSING - """Scaling of the joint efforts output from the network.""" - - input_order: Literal["pos_vel", "vel_pos"] = MISSING - """Order of the inputs to the network. - - The order can be one of the following: - - * ``"pos_vel"``: joint position errors followed by joint velocities - * ``"vel_pos"``: joint velocities followed by joint position errors - """ - - input_idx: Iterable[int] = MISSING - """ - Indices of the actuator history buffer passed as inputs to the network. - - The index *0* corresponds to current time-step, while *n* corresponds to n-th - time-step in the past. The allocated history length is `max(input_idx) + 1`. - """ - - -@configclass -class DelayedPDActuatorCfg(IdealPDActuatorCfg): - """Configuration for a delayed PD actuator.""" - - class_type: type = actuator_pd.DelayedPDActuator - - min_delay: int = 0 - """Minimum number of physics time-steps with which the actuator command may be delayed. Defaults to 0.""" - - max_delay: int = 0 - """Maximum number of physics time-steps with which the actuator command may be delayed. Defaults to 0.""" - - -@configclass -class RemotizedPDActuatorCfg(DelayedPDActuatorCfg): - """Configuration for a remotized PD actuator. - - Note: - The torque output limits for this actuator is derived from a linear interpolation of a lookup table - in :attr:`joint_parameter_lookup`. This table describes the relationship between joint angles and - the output torques. - """ - - class_type: type = actuator_pd.RemotizedPDActuator - - joint_parameter_lookup: list[list[float]] = MISSING - """Joint parameter lookup table. Shape is (num_lookup_points, 3). - - This tensor describes the relationship between the joint angle (rad), the transmission ratio (in/out), - and the output torque (N*m). The table is used to interpolate the output torque based on the joint angle. - """ diff --git a/source/isaaclab/isaaclab/actuators/actuator_net.py b/source/isaaclab/isaaclab/actuators/actuator_net.py index 9b4b1641f2c..fc40261c774 100644 --- a/source/isaaclab/isaaclab/actuators/actuator_net.py +++ b/source/isaaclab/isaaclab/actuators/actuator_net.py @@ -24,7 +24,7 @@ from .actuator_pd import DCMotor if TYPE_CHECKING: - from .actuator_cfg import ActuatorNetLSTMCfg, ActuatorNetMLPCfg + from .actuator_net_cfg import ActuatorNetLSTMCfg, ActuatorNetMLPCfg class ActuatorNetLSTM(DCMotor): diff --git a/source/isaaclab/isaaclab/actuators/actuator_net_cfg.py b/source/isaaclab/isaaclab/actuators/actuator_net_cfg.py new file mode 100644 index 00000000000..9035cf8ab78 --- /dev/null +++ b/source/isaaclab/isaaclab/actuators/actuator_net_cfg.py @@ -0,0 +1,64 @@ +# Copyright (c) 2022-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 collections.abc import Iterable +from dataclasses import MISSING +from typing import Literal + +from isaaclab.utils import configclass + +from . import actuator_net +from .actuator_pd_cfg import DCMotorCfg + + +@configclass +class ActuatorNetLSTMCfg(DCMotorCfg): + """Configuration for LSTM-based actuator model.""" + + class_type: type = actuator_net.ActuatorNetLSTM + # we don't use stiffness and damping for actuator net + stiffness = None + damping = None + + network_file: str = MISSING + """Path to the file containing network weights.""" + + +@configclass +class ActuatorNetMLPCfg(DCMotorCfg): + """Configuration for MLP-based actuator model.""" + + class_type: type = actuator_net.ActuatorNetMLP + # we don't use stiffness and damping for actuator net + + stiffness = None + damping = None + + network_file: str = MISSING + """Path to the file containing network weights.""" + + pos_scale: float = MISSING + """Scaling of the joint position errors input to the network.""" + vel_scale: float = MISSING + """Scaling of the joint velocities input to the network.""" + torque_scale: float = MISSING + """Scaling of the joint efforts output from the network.""" + + input_order: Literal["pos_vel", "vel_pos"] = MISSING + """Order of the inputs to the network. + + The order can be one of the following: + + * ``"pos_vel"``: joint position errors followed by joint velocities + * ``"vel_pos"``: joint velocities followed by joint position errors + """ + + input_idx: Iterable[int] = MISSING + """ + Indices of the actuator history buffer passed as inputs to the network. + + The index *0* corresponds to current time-step, while *n* corresponds to n-th + time-step in the past. The allocated history length is `max(input_idx) + 1`. + """ diff --git a/source/isaaclab/isaaclab/actuators/actuator_pd.py b/source/isaaclab/isaaclab/actuators/actuator_pd.py index 162005dfd17..cd774c3abde 100644 --- a/source/isaaclab/isaaclab/actuators/actuator_pd.py +++ b/source/isaaclab/isaaclab/actuators/actuator_pd.py @@ -17,7 +17,7 @@ from .actuator_base import ActuatorBase if TYPE_CHECKING: - from .actuator_cfg import ( + from .actuator_pd_cfg import ( DCMotorCfg, DelayedPDActuatorCfg, IdealPDActuatorCfg, @@ -377,41 +377,17 @@ class RemotizedPDActuator(DelayedPDActuator): def __init__( self, cfg: RemotizedPDActuatorCfg, - joint_names: list[str], - joint_ids: Sequence[int], - num_envs: int, - device: str, - stiffness: torch.Tensor | float = 0.0, - damping: torch.Tensor | float = 0.0, - armature: torch.Tensor | float = 0.0, - friction: torch.Tensor | float = 0.0, - dynamic_friction: torch.Tensor | float = 0.0, - viscous_friction: torch.Tensor | float = 0.0, - effort_limit: torch.Tensor | float = torch.inf, - velocity_limit: torch.Tensor | float = torch.inf, + *args, + **kwargs, ): # remove effort and velocity box constraints from the base class cfg.effort_limit = torch.inf cfg.velocity_limit = torch.inf # call the base method and set default effort_limit and velocity_limit to inf - super().__init__( - cfg, - joint_names, - joint_ids, - num_envs, - device, - stiffness, - damping, - armature, - friction, - dynamic_friction, - viscous_friction, - effort_limit, - velocity_limit, - ) - self._joint_parameter_lookup = torch.tensor(cfg.joint_parameter_lookup, device=device) + super().__init__(cfg, *args, **kwargs) + self._joint_parameter_lookup = torch.tensor(cfg.joint_parameter_lookup, device=self._device) # define remotized joint torque limit - self._torque_limit = LinearInterpolation(self.angle_samples, self.max_torque_samples, device=device) + self._torque_limit = LinearInterpolation(self.angle_samples, self.max_torque_samples, device=self._device) """ Properties. diff --git a/source/isaaclab/isaaclab/actuators/actuator_pd_cfg.py b/source/isaaclab/isaaclab/actuators/actuator_pd_cfg.py new file mode 100644 index 00000000000..35d40278e2c --- /dev/null +++ b/source/isaaclab/isaaclab/actuators/actuator_pd_cfg.py @@ -0,0 +1,81 @@ +# Copyright (c) 2022-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 dataclasses import MISSING + +from isaaclab.utils import configclass + +from . import actuator_pd +from .actuator_base_cfg import ActuatorBaseCfg + +""" +Implicit Actuator Models. +""" + + +@configclass +class ImplicitActuatorCfg(ActuatorBaseCfg): + """Configuration for an implicit actuator. + + Note: + The PD control is handled implicitly by the simulation. + """ + + class_type: type = actuator_pd.ImplicitActuator + + +""" +Explicit Actuator Models. +""" + + +@configclass +class IdealPDActuatorCfg(ActuatorBaseCfg): + """Configuration for an ideal PD actuator.""" + + class_type: type = actuator_pd.IdealPDActuator + + +@configclass +class DCMotorCfg(IdealPDActuatorCfg): + """Configuration for direct control (DC) motor actuator model.""" + + class_type: type = actuator_pd.DCMotor + + saturation_effort: float = MISSING + """Peak motor force/torque of the electric DC motor (in N-m).""" + + +@configclass +class DelayedPDActuatorCfg(IdealPDActuatorCfg): + """Configuration for a delayed PD actuator.""" + + class_type: type = actuator_pd.DelayedPDActuator + + min_delay: int = 0 + """Minimum number of physics time-steps with which the actuator command may be delayed. Defaults to 0.""" + + max_delay: int = 0 + """Maximum number of physics time-steps with which the actuator command may be delayed. Defaults to 0.""" + + +@configclass +class RemotizedPDActuatorCfg(DelayedPDActuatorCfg): + """Configuration for a remotized PD actuator. + + Note: + The torque output limits for this actuator is derived from a linear interpolation of a lookup table + in :attr:`joint_parameter_lookup`. This table describes the relationship between joint angles and + the output torques. + """ + + class_type: type = actuator_pd.RemotizedPDActuator + + joint_parameter_lookup: list[list[float]] = MISSING + """Joint parameter lookup table. Shape is (num_lookup_points, 3). + + This tensor describes the relationship between the joint angle (rad), the transmission ratio (in/out), + and the output torque (N*m). The table is used to interpolate the output torque based on the joint angle. + """ diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation.py b/source/isaaclab/isaaclab/assets/articulation/articulation.py index deb8b6479f5..8d2d4f672bb 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation.py @@ -328,7 +328,6 @@ def write_root_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[in def write_root_com_state_to_sim(self, root_state: torch.Tensor, env_ids: Sequence[int] | None = None): """Set the root center of mass state over selected environment indices into the simulation. - The root state comprises of the cartesian position, quaternion orientation in (w, x, y, z), and linear and angular velocity. All the quantities are in the simulation frame. @@ -793,6 +792,47 @@ def write_joint_effort_limit_to_sim( # set into simulation self.root_physx_view.set_dof_max_forces(self._data.joint_effort_limits.cpu(), indices=physx_env_ids.cpu()) + def write_joint_drive_model_to_sim( + self, + drive_params: torch.Tensor | tuple[float, float, float] | None = None, + joint_ids: Sequence[int] | slice | None = None, + env_ids: Sequence[int] | None = None, + ): + """Write parameters (in additional to max forces) necessary to model motor drive performance envelopes. + + Additional parameters can be provided to improve sim-to-real transfer by more accurately modeling the motor drive's + performance envelope. Specifically, we define linear constraints on the torque-speed boundary and the speed-torque + boundary by defining a speed-effort grandient, maximum actuator velocity, and velocity dependent resistance for each + motor in the articulation. See: https://docs.omniverse.nvidia.com/kit/docs/omni_physics/107.3/_downloads/f44e831b7f29e7c2ec8e3f2c54418430/drivePerformanceEnvelope.pdf + + Args: + drive_params: The drive parameters. Shape is (len(env_ids), len(joint_ids), 3). The final three dimensions + reflect the speed-effort gradient, max actuator velocity, and velocity dependent resistance + respectively. + joint_ids: The joint indices to set the joint torque limits for. Defaults to None (all joints). + env_ids: The environment indices to set the joint torque limits for. Defaults to None (all environments). + """ + if int(get_version()[2]) >= 5: + # resolve indices + physx_env_ids = env_ids + if env_ids is None: + env_ids = slice(None) + physx_env_ids = self._ALL_INDICES + if joint_ids is None: + joint_ids = slice(None) + # broadcast env_ids if needed to allow double indexing + if env_ids != slice(None) and joint_ids != slice(None): + env_ids = env_ids[:, None] + # move tensor to cpu if needed + if isinstance(drive_params, torch.Tensor): + drive_params = drive_params.to(self.device) + # set into internal buffers + self._data.joint_drive_model_parameters[env_ids, joint_ids] = drive_params + # set into simulation + self.root_physx_view.set_dof_drive_model_properties( + self._data.joint_drive_model_parameters.cpu(), indices=physx_env_ids.cpu() + ) + def write_joint_armature_to_sim( self, armature: torch.Tensor | float, @@ -1594,6 +1634,12 @@ def _create_buffers(self): self._data.joint_pos_limits = self._data.default_joint_pos_limits.clone() self._data.joint_vel_limits = self.root_physx_view.get_dof_max_velocities().to(self.device).clone() self._data.joint_effort_limits = self.root_physx_view.get_dof_max_forces().to(self.device).clone() + if int(get_version()[2]) >= 5: + self._data.default_joint_drive_model_parameters = ( + self.root_physx_view.get_dof_drive_model_properties().to(self.device).clone() + ) + self._data.joint_drive_model_parameters = self._data.default_joint_drive_model_parameters.clone() + self._data.joint_stiffness = self._data.default_joint_stiffness.clone() self._data.joint_damping = self._data.default_joint_damping.clone() self._data.joint_armature = self._data.default_joint_armature.clone() @@ -1701,6 +1747,7 @@ def _process_actuators_cfg(self): joint_ids = torch.tensor(joint_ids, device=self.device) # create actuator collection # note: for efficiency avoid indexing when over all indices + actuator: ActuatorBase = actuator_cfg.class_type( cfg=actuator_cfg, joint_names=joint_names, @@ -1715,6 +1762,11 @@ def _process_actuators_cfg(self): viscous_friction=self._data.default_joint_viscous_friction_coeff[:, joint_ids], effort_limit=self._data.joint_effort_limits[:, joint_ids], velocity_limit=self._data.joint_vel_limits[:, joint_ids], + drive_model=( + self._data.joint_drive_model_parameters[:, joint_ids] + if int(get_version()[2]) >= 5 + else ActuatorBaseCfg.DriveModelCfg() + ), ) # log information on actuator groups model_type = "implicit" if actuator.is_implicit_model else "explicit" @@ -1742,6 +1794,7 @@ def _process_actuators_cfg(self): self.write_joint_armature_to_sim(actuator.armature, joint_ids=actuator.joint_indices) self.write_joint_friction_coefficient_to_sim(actuator.friction, joint_ids=actuator.joint_indices) if int(get_version()[2]) >= 5: + self.write_joint_drive_model_to_sim(actuator.drive_model, joint_ids=actuator.joint_indices) self.write_joint_dynamic_friction_coefficient_to_sim( actuator.dynamic_friction, joint_ids=actuator.joint_indices ) @@ -1758,7 +1811,7 @@ def _process_actuators_cfg(self): if int(get_version()[2]) >= 5: self._data.default_joint_dynamic_friction_coeff[:, actuator.joint_indices] = actuator.dynamic_friction self._data.default_joint_viscous_friction_coeff[:, actuator.joint_indices] = actuator.viscous_friction - + self._data.default_joint_drive_model_parameters[:, actuator.joint_indices] = actuator.drive_model # perform some sanity checks to ensure actuators are prepared correctly total_act_joints = sum(actuator.num_joints for actuator in self.actuators.values()) if total_act_joints != (self.num_joints - self.num_fixed_tendons): @@ -1775,7 +1828,16 @@ def _process_actuators_cfg(self): for prop_idx, resolution_detail in enumerate(resolution_details): actuator_group_str = actuator_group if group_count == 0 else "" property_str = property if prop_idx == 0 else "" - fmt = [f"{v:.2e}" if isinstance(v, float) else str(v) for v in resolution_detail] + fmt = [ + ( + f"{v:.2e}" + if isinstance(v, float) + else ( + "(" + ", ".join([f"{vt:.2e}" for vt in v]) + ")" if isinstance(v, tuple) else str(v) + ) + ) + for v in resolution_detail + ] t.add_row([actuator_group_str, property_str, *fmt]) group_count += 1 omni.log.warn(f"\nActuatorCfg-USD Value Discrepancy Resolution (matching values are skipped): \n{t}") diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation_data.py b/source/isaaclab/isaaclab/assets/articulation/articulation_data.py index 6d974dd37d6..0fc8ed04cf5 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation_data.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation_data.py @@ -286,6 +286,10 @@ def update(self, dt: float): This quantity is parsed from the USD schema at the time of initialization. """ + default_joint_drive_model_parameters: torch.Tensor = None + """Default joint drive model parameters. Shape is (num_instances, num_drive_models, 3). The last indices reflect + the speed_effort_gradient, the max_actuator_velocity, and the velocity_dependent_resistance respectively.""" + ## # Joint commands -- Set into simulation. ## @@ -381,6 +385,9 @@ def update(self, dt: float): joint_effort_limits: torch.Tensor = None """Joint maximum effort provided to the simulation. Shape is (num_instances, num_joints).""" + joint_drive_model_parameters = None + """Joint drive model parameters provided to the simulation. Shape is (num_instances, num_joints, 3).""" + ## # Joint properties - Custom. ## diff --git a/source/isaaclab/test/actuators/test_drive_model_properties.py b/source/isaaclab/test/actuators/test_drive_model_properties.py new file mode 100644 index 00000000000..7402544d910 --- /dev/null +++ b/source/isaaclab/test/actuators/test_drive_model_properties.py @@ -0,0 +1,69 @@ +# 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 IdealPDActuatorCfg + + +@pytest.mark.parametrize("num_envs", [1, 2]) +@pytest.mark.parametrize("num_joints", [1, 2]) +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +def test_init_drive_model(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 + velocity_limit = 50 + drive_model = IdealPDActuatorCfg.DriveModelCfg( + speed_effort_gradient=100.0, + max_actuator_velocity=200.0, + velocity_dependent_resistance=0.1, + ) + + actuator_cfg = IdealPDActuatorCfg( + joint_names_expr=joint_names, + stiffness=stiffness, + damping=damping, + effort_limit=effort_limit, + velocity_limit=velocity_limit, + drive_model=drive_model, + ) + # 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.drive_model[:, :, 2], + drive_model.velocity_dependent_resistance * torch.ones(num_envs, num_joints, device=device), + ) + torch.testing.assert_close( + actuator.drive_model[:, :, 1], + drive_model.max_actuator_velocity * torch.ones(num_envs, num_joints, device=device), + ) + torch.testing.assert_close( + actuator.drive_model[:, :, 0], + drive_model.speed_effort_gradient * torch.ones(num_envs, num_joints, device=device), + ) diff --git a/source/isaaclab/test/assets/test_articulation.py b/source/isaaclab/test/assets/test_articulation.py index dfacff5d2ec..6d3c6bd40b4 100644 --- a/source/isaaclab/test/assets/test_articulation.py +++ b/source/isaaclab/test/assets/test_articulation.py @@ -48,6 +48,7 @@ def generate_articulation_cfg( effort_limit: float | None = None, velocity_limit_sim: float | None = None, effort_limit_sim: float | None = None, + drive_model: tuple[float, float, float] | None = None, ) -> ArticulationCfg: """Generate an articulation configuration. @@ -67,11 +68,13 @@ def generate_articulation_cfg( Only currently used for "single_joint_implicit" and "single_joint_explicit". effort_limit_sim: Effort limit for the actuators (set into the simulation). Only currently used for "single_joint_implicit" and "single_joint_explicit". + drive_model: Drive model parameters for the actuators. + Only currently used for "single_joint_implicit" and "single_joint_explicit". Returns: The articulation configuration for the requested articulation type. - """ + if articulation_type == "humanoid": articulation_cfg = ArticulationCfg( spawn=sim_utils.UsdFileCfg( @@ -102,6 +105,7 @@ def generate_articulation_cfg( velocity_limit=velocity_limit, stiffness=2000.0, damping=100.0, + drive_model=drive_model, ), }, init_state=ArticulationCfg.InitialStateCfg( @@ -126,6 +130,7 @@ def generate_articulation_cfg( velocity_limit=velocity_limit, stiffness=0.0, damping=10.0, + drive_model=drive_model, ), }, ) @@ -1369,6 +1374,84 @@ def test_setting_velocity_limit_explicit(sim, num_articulations, device, vel_lim torch.testing.assert_close(physx_vel_limit, expected_vel_limit) +@pytest.mark.parametrize("num_articulations", [1, 2]) +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.parametrize("drive_model", [(100.0, 200.0, 0.1), None]) +@pytest.mark.skipif(int(get_version()[2]) < 5, reason="Simulator version must be 5 or greater") +@pytest.mark.isaacsim_ci +def test_setting_drive_model_explicit(sim, num_articulations, device, drive_model): + """Test setting of velocity limit for explicit actuators.""" + articulation_cfg = generate_articulation_cfg(articulation_type="single_joint_explicit", drive_model=drive_model) + articulation, _ = generate_articulation( + articulation_cfg=articulation_cfg, + num_articulations=num_articulations, + device=device, + ) + # Play sim + sim.reset() + + # collect dm init values + physx_dm = articulation.root_physx_view.get_dof_drive_model_properties().to(device) + actuator_dm = articulation.actuators["joint"].drive_model + + # check data buffer for joint_ + torch.testing.assert_close(articulation.data.joint_drive_model_parameters, physx_dm) + + if drive_model is not None: + expected_actuator_dm = torch.zeros( + (articulation.num_instances, articulation.num_joints, 3), + device=articulation.device, + ) + expected_actuator_dm[:, :, 0] = drive_model[0] + expected_actuator_dm[:, :, 1] = drive_model[1] + expected_actuator_dm[:, :, 2] = drive_model[2] + + # check actuator is set + torch.testing.assert_close(actuator_dm, expected_actuator_dm) + else: + # check actuator velocity_limit is the same as the PhysX default + torch.testing.assert_close(actuator_dm, physx_dm) + + +@pytest.mark.parametrize("num_articulations", [1, 2]) +@pytest.mark.parametrize("device", ["cuda:0", "cpu"]) +@pytest.mark.parametrize("drive_model", [(100.0, 200.0, 0.1), None]) +@pytest.mark.skipif(int(get_version()[2]) < 5, reason="Simulator version must be 5 or greater") +@pytest.mark.isaacsim_ci +def test_setting_drive_model_implicit(sim, num_articulations, device, drive_model): + """Test setting of velocity limit for explicit actuators.""" + articulation_cfg = generate_articulation_cfg(articulation_type="single_joint_implicit", drive_model=drive_model) + articulation, _ = generate_articulation( + articulation_cfg=articulation_cfg, + num_articulations=num_articulations, + device=device, + ) + # Play sim + sim.reset() + + # collect dm init values + physx_dm = articulation.root_physx_view.get_dof_drive_model_properties().to(device) + actuator_dm = articulation.actuators["joint"].drive_model + + # check data buffer for joint_ + torch.testing.assert_close(articulation.data.joint_drive_model_parameters, physx_dm) + + if drive_model is not None: + expected_actuator_dm = torch.zeros( + (articulation.num_instances, articulation.num_joints, 3), + device=articulation.device, + ) + expected_actuator_dm[:, :, 0] = drive_model[0] + expected_actuator_dm[:, :, 1] = drive_model[1] + expected_actuator_dm[:, :, 2] = drive_model[2] + + # check actuator is set + torch.testing.assert_close(actuator_dm, expected_actuator_dm) + else: + # check actuator velocity_limit is the same as the PhysX default + torch.testing.assert_close(actuator_dm, physx_dm) + + @pytest.mark.parametrize("num_articulations", [1, 2]) @pytest.mark.parametrize("device", ["cuda:0", "cpu"]) @pytest.mark.parametrize("effort_limit_sim", [1e5, None]) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/allegro.py b/source/isaaclab_assets/isaaclab_assets/robots/allegro.py index abc601aa283..26bec4c5fd0 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/allegro.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/allegro.py @@ -19,7 +19,7 @@ import math import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py b/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py index d6c86bb3f15..2ca955cd1e8 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py @@ -17,7 +17,7 @@ """ import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR diff --git a/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py b/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py index 79696aab091..47e3f3d5840 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py @@ -17,7 +17,7 @@ import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py index 78cb3d3da6a..68d28ace75d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py @@ -4,7 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py index 6f6630a3eb8..64b09ea81c5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py @@ -4,7 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py index 735efa306d6..72a08b06941 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py @@ -4,7 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py index 8e0aab5b0c7..53dc7cf8ffb 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py @@ -12,7 +12,7 @@ from pxr import UsdGeom import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import Articulation, ArticulationCfg from isaaclab.envs import DirectRLEnv, DirectRLEnvCfg from isaaclab.scene import InteractiveSceneCfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py index b6a3702eab8..ba2e9ac946e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py @@ -7,7 +7,7 @@ from dataclasses import MISSING import isaaclab.sim as sim_utils -from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.envs import ManagerBasedRLEnvCfg from isaaclab.managers import EventTermCfg as EventTerm