From 4b5e348c74ebc5204e66b3dd5ad43883571f1fe9 Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Thu, 26 Feb 2026 20:13:37 -0800 Subject: [PATCH] add resolvable string --- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 16 +++++ .../isaaclab/actuators/actuator_net_cfg.py | 10 +-- .../isaaclab/actuators/actuator_pd_cfg.py | 15 ++-- .../assets/articulation/articulation_cfg.py | 7 +- source/isaaclab/isaaclab/assets/asset_base.py | 6 +- .../isaaclab/assets/asset_base_cfg.py | 4 +- .../assets/rigid_object/rigid_object_cfg.py | 8 ++- .../rigid_object_collection_cfg.py | 6 +- .../controllers/differential_ik_cfg.py | 7 +- .../controllers/operational_space_cfg.py | 6 +- .../devices/gamepad/se2_gamepad_cfg.py | 7 +- .../devices/gamepad/se3_gamepad_cfg.py | 7 +- .../devices/keyboard/se2_keyboard_cfg.py | 7 +- .../devices/keyboard/se3_keyboard_cfg.py | 7 +- .../devices/spacemouse/se2_spacemouse.py | 2 +- .../devices/spacemouse/se2_spacemouse_cfg.py | 7 +- .../devices/spacemouse/se3_spacemouse_cfg.py | 7 +- .../isaaclab/envs/direct_marl_env_cfg.py | 3 +- .../isaaclab/envs/direct_rl_env_cfg.py | 3 +- .../isaaclab/envs/manager_based_env_cfg.py | 3 +- .../isaaclab/envs/manager_based_rl_env_cfg.py | 3 +- .../isaaclab/envs/mdp/actions/actions_cfg.py | 50 +++++++------ .../envs/mdp/actions/pink_actions_cfg.py | 8 ++- .../envs/mdp/actions/rmpflow_actions_cfg.py | 10 +-- .../envs/mdp/commands/commands_cfg.py | 22 +++--- .../envs/mdp/recorders/recorders_cfg.py | 25 +++++-- .../isaaclab/envs/ui/base_env_window.py | 8 +-- .../isaaclab/sensors/camera/camera_cfg.py | 8 ++- .../sensors/camera/tiled_camera_cfg.py | 8 ++- .../contact_sensor/contact_sensor_cfg.py | 8 ++- .../frame_transformer_cfg.py | 7 +- .../isaaclab/isaaclab/sensors/imu/imu_cfg.py | 8 ++- .../multi_mesh_ray_caster_camera_cfg.py | 7 +- .../ray_caster/multi_mesh_ray_caster_cfg.py | 7 +- .../ray_caster/ray_caster_camera_cfg.py | 8 ++- .../sensors/ray_caster/ray_caster_cfg.py | 8 ++- .../isaaclab/isaaclab/sensors/sensor_base.py | 6 +- .../sim/spawners/from_files/from_files_cfg.py | 12 ++-- .../sim/spawners/lights/lights_cfg.py | 4 +- .../materials/physics_materials_cfg.py | 6 +- .../materials/visual_materials_cfg.py | 8 +-- .../sim/spawners/meshes/meshes_cfg.py | 12 ++-- .../sim/spawners/sensors/sensors_cfg.py | 6 +- .../sim/spawners/shapes/shapes_cfg.py | 12 ++-- .../isaaclab/sim/spawners/spawner_cfg.py | 9 ++- .../sim/spawners/wrappers/wrappers_cfg.py | 6 +- .../terrains/height_field/hf_terrains_cfg.py | 13 ++-- .../terrains/terrain_generator_cfg.py | 8 ++- .../isaaclab/terrains/terrain_importer_cfg.py | 5 +- .../terrains/trimesh/mesh_terrains_cfg.py | 30 ++++---- source/isaaclab/isaaclab/utils/configclass.py | 44 +++++++++++- source/isaaclab/isaaclab/utils/dict.py | 21 ++++-- .../isaaclab/utils/noise/noise_cfg.py | 15 ++-- source/isaaclab/isaaclab/utils/string.py | 70 +++++++++++++++++++ source/isaaclab/test/utils/test_dict.py | 28 ++++++++ source/isaaclab/test/utils/test_string.py | 38 ++++++++++ .../actuators/thruster_cfg.py | 7 +- .../assets/multirotor/multirotor_cfg.py | 6 +- .../mdp/actions/thrust_actions_cfg.py | 8 ++- .../tacsl_sensor/visuotactile_sensor_cfg.py | 6 +- .../envs/locomanipulation_sdg_env_cfg.py | 6 +- .../deformable_object_cfg.py | 7 +- .../surface_gripper/surface_gripper_cfg.py | 6 +- .../physics/physx_manager_cfg.py | 6 +- .../direct/quadcopter/quadcopter_env_cfg.py | 3 +- .../drone_arl/mdp/commands/commands_cfg.py | 7 +- .../pick_place/configs/action_cfg.py | 10 ++- .../mdp/commands/pose_commands_cfg.py | 6 +- .../inhand/mdp/commands/commands_cfg.py | 5 +- .../mdp/pre_trained_policy_action.py | 2 + .../mdp/pre_trained_policy_action_cfg.py | 4 +- 72 files changed, 532 insertions(+), 245 deletions(-) diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 73085deba3f..56e7a261123 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 = "4.2.2" +version = "4.3.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index ea4471ed43c..bb67104d6eb 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,22 @@ Changelog --------- +4.3.0 (2026-02-26) +~~~~~~~~~~~~~~~~~~ + +Changed +^^^^^^^ + +* Added lazy callable-string resolution for config fields through + :class:`~isaaclab.utils.string.ResolvableString` in :mod:`isaaclab.utils.configclass`. + Config values such as ``class_type``/``func`` can now remain as strings until first + use and then resolve/cached automatically. + +* Added ``{DIR}`` callable-string shorthand support in :mod:`isaaclab.utils.configclass` + for config defaults. ``"{DIR}.module:Symbol"`` now expands to the declaring config + module directory before resolution. + + 4.2.2 (2026-02-26) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/actuators/actuator_net_cfg.py b/source/isaaclab/isaaclab/actuators/actuator_net_cfg.py index eecfe8050ab..ab8f53151b7 100644 --- a/source/isaaclab/isaaclab/actuators/actuator_net_cfg.py +++ b/source/isaaclab/isaaclab/actuators/actuator_net_cfg.py @@ -5,19 +5,21 @@ from collections.abc import Iterable from dataclasses import MISSING -from typing import Literal +from typing import TYPE_CHECKING, Literal from isaaclab.utils import configclass -from . import actuator_net from .actuator_pd_cfg import DCMotorCfg +if TYPE_CHECKING: + from .actuator_net import ActuatorNetLSTM, ActuatorNetMLP + @configclass class ActuatorNetLSTMCfg(DCMotorCfg): """Configuration for LSTM-based actuator model.""" - class_type: type = actuator_net.ActuatorNetLSTM + class_type: type["ActuatorNetLSTM"] | str = "{DIR}.actuator_net:ActuatorNetLSTM" # we don't use stiffness and damping for actuator net stiffness = None damping = None @@ -30,7 +32,7 @@ class ActuatorNetLSTMCfg(DCMotorCfg): class ActuatorNetMLPCfg(DCMotorCfg): """Configuration for MLP-based actuator model.""" - class_type: type = actuator_net.ActuatorNetMLP + class_type: type["ActuatorNetMLP"] | str = "{DIR}.actuator_net:ActuatorNetMLP" # we don't use stiffness and damping for actuator net stiffness = None diff --git a/source/isaaclab/isaaclab/actuators/actuator_pd_cfg.py b/source/isaaclab/isaaclab/actuators/actuator_pd_cfg.py index d1f5a6282ad..a57a7b3b7f6 100644 --- a/source/isaaclab/isaaclab/actuators/actuator_pd_cfg.py +++ b/source/isaaclab/isaaclab/actuators/actuator_pd_cfg.py @@ -4,12 +4,15 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.utils import configclass -from . import actuator_pd from .actuator_base_cfg import ActuatorBaseCfg +if TYPE_CHECKING: + from .actuator_pd import DCMotor, DelayedPDActuator, IdealPDActuator, ImplicitActuator, RemotizedPDActuator + """ Implicit Actuator Models. """ @@ -23,7 +26,7 @@ class ImplicitActuatorCfg(ActuatorBaseCfg): The PD control is handled implicitly by the simulation. """ - class_type: type = actuator_pd.ImplicitActuator + class_type: type["ImplicitActuator"] | str = "{DIR}.actuator_pd:ImplicitActuator" """ @@ -35,14 +38,14 @@ class ImplicitActuatorCfg(ActuatorBaseCfg): class IdealPDActuatorCfg(ActuatorBaseCfg): """Configuration for an ideal PD actuator.""" - class_type: type = actuator_pd.IdealPDActuator + class_type: type["IdealPDActuator"] | str = "{DIR}.actuator_pd:IdealPDActuator" @configclass class DCMotorCfg(IdealPDActuatorCfg): """Configuration for direct control (DC) motor actuator model.""" - class_type: type = actuator_pd.DCMotor + class_type: type["DCMotor"] | str = "{DIR}.actuator_pd:DCMotor" saturation_effort: float = MISSING """Peak motor force/torque of the electric DC motor (in N-m).""" @@ -52,7 +55,7 @@ class DCMotorCfg(IdealPDActuatorCfg): class DelayedPDActuatorCfg(IdealPDActuatorCfg): """Configuration for a delayed PD actuator.""" - class_type: type = actuator_pd.DelayedPDActuator + class_type: type["DelayedPDActuator"] | str = "{DIR}.actuator_pd:DelayedPDActuator" min_delay: int = 0 """Minimum number of physics time-steps with which the actuator command may be delayed. Defaults to 0.""" @@ -71,7 +74,7 @@ class RemotizedPDActuatorCfg(DelayedPDActuatorCfg): the output torques. """ - class_type: type = actuator_pd.RemotizedPDActuator + class_type: type["RemotizedPDActuator"] | str = "{DIR}.actuator_pd:RemotizedPDActuator" joint_parameter_lookup: list[list[float]] = MISSING """Joint parameter lookup table. Shape is (num_lookup_points, 3). diff --git a/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py b/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py index f8c558302d3..d3d94a9b23e 100644 --- a/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py +++ b/source/isaaclab/isaaclab/assets/articulation/articulation_cfg.py @@ -6,12 +6,15 @@ from __future__ import annotations from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.actuators import ActuatorBaseCfg from isaaclab.utils import configclass from ..asset_base_cfg import AssetBaseCfg -from .articulation import Articulation + +if TYPE_CHECKING: + from .articulation import Articulation @configclass @@ -38,7 +41,7 @@ class InitialStateCfg(AssetBaseCfg.InitialStateCfg): # Initialize configurations. ## - class_type: type = Articulation + class_type: type[Articulation] | str = "{DIR}.articulation:Articulation" articulation_root_prim_path: str | None = None """Path to the articulation root prim under the :attr:`prim_path`. Defaults to None, in which case the class diff --git a/source/isaaclab/isaaclab/assets/asset_base.py b/source/isaaclab/isaaclab/assets/asset_base.py index a276b019c22..1e3f8b8d538 100644 --- a/source/isaaclab/isaaclab/assets/asset_base.py +++ b/source/isaaclab/isaaclab/assets/asset_base.py @@ -16,7 +16,7 @@ import warp as wp import isaaclab.sim as sim_utils -from isaaclab.physics import PhysicsEvent, PhysicsManager +from isaaclab.physics import PhysicsEvent from isaaclab.sim.simulation_context import SimulationContext from isaaclab.sim.utils.stage import get_current_stage @@ -381,8 +381,8 @@ def _initialize_callback(self, event): :attr:`PhysicsEvent.PHYSICS_READY` is dispatched by the current backend. """ if not self._is_initialized: - self._backend = PhysicsManager.get_backend() - self._device = PhysicsManager.get_device() + self._backend = SimulationContext.instance().physics_manager.get_backend() + self._device = SimulationContext.instance().physics_manager.get_device() try: self._initialize_impl() except Exception as e: diff --git a/source/isaaclab/isaaclab/assets/asset_base_cfg.py b/source/isaaclab/isaaclab/assets/asset_base_cfg.py index cb24b8f632d..37d551ddec7 100644 --- a/source/isaaclab/isaaclab/assets/asset_base_cfg.py +++ b/source/isaaclab/isaaclab/assets/asset_base_cfg.py @@ -11,8 +11,6 @@ from isaaclab.sim import SpawnerCfg from isaaclab.utils import configclass -from .asset_base import AssetBase - @configclass class AssetBaseCfg: @@ -41,7 +39,7 @@ class InitialStateCfg: Defaults to (0.0, 0.0, 0.0, 1.0). """ - class_type: type[AssetBase] = None + class_type: type | str | None = None """The associated asset class. Defaults to None, which means that the asset will be spawned but cannot be interacted with via the asset class. diff --git a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_cfg.py b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_cfg.py index 8340aa45f76..099bbdeea78 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_cfg.py +++ b/source/isaaclab/isaaclab/assets/rigid_object/rigid_object_cfg.py @@ -3,10 +3,14 @@ # # SPDX-License-Identifier: BSD-3-Clause +from typing import TYPE_CHECKING + from isaaclab.utils import configclass from ..asset_base_cfg import AssetBaseCfg -from .rigid_object import RigidObject + +if TYPE_CHECKING: + from .rigid_object import RigidObject @configclass @@ -26,7 +30,7 @@ class InitialStateCfg(AssetBaseCfg.InitialStateCfg): # Initialize configurations. ## - class_type: type = RigidObject + class_type: type["RigidObject"] | str = "{DIR}.rigid_object:RigidObject" init_state: InitialStateCfg = InitialStateCfg() """Initial state of the rigid object. Defaults to identity pose with zero velocity.""" diff --git a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_cfg.py b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_cfg.py index c99b20044dd..a094a8968dd 100644 --- a/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_cfg.py +++ b/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_cfg.py @@ -4,18 +4,20 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.assets.rigid_object import RigidObjectCfg from isaaclab.utils import configclass -from .rigid_object_collection import RigidObjectCollection +if TYPE_CHECKING: + from .rigid_object_collection import RigidObjectCollection @configclass class RigidObjectCollectionCfg: """Configuration parameters for a rigid object collection.""" - class_type: type = RigidObjectCollection + class_type: type["RigidObjectCollection"] | str = "{DIR}.rigid_object_collection:RigidObjectCollection" """The associated asset class. The class should inherit from :class:`isaaclab.assets.asset_base.AssetBase`. diff --git a/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py b/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py index ce30b131ba7..f596ce75f63 100644 --- a/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py +++ b/source/isaaclab/isaaclab/controllers/differential_ik_cfg.py @@ -6,18 +6,19 @@ from __future__ import annotations from dataclasses import MISSING -from typing import Literal +from typing import TYPE_CHECKING, Literal from isaaclab.utils import configclass -from .differential_ik import DifferentialIKController +if TYPE_CHECKING: + from .differential_ik import DifferentialIKController @configclass class DifferentialIKControllerCfg: """Configuration for differential inverse kinematics controller.""" - class_type: type = DifferentialIKController + class_type: type[DifferentialIKController] | str = "{DIR}.differential_ik:DifferentialIKController" """The associated controller class.""" command_type: Literal["position", "pose"] = MISSING diff --git a/source/isaaclab/isaaclab/controllers/operational_space_cfg.py b/source/isaaclab/isaaclab/controllers/operational_space_cfg.py index 5572ae43925..280caf7d32d 100644 --- a/source/isaaclab/isaaclab/controllers/operational_space_cfg.py +++ b/source/isaaclab/isaaclab/controllers/operational_space_cfg.py @@ -7,17 +7,19 @@ from collections.abc import Sequence from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.utils import configclass -from .operational_space import OperationalSpaceController +if TYPE_CHECKING: + from .operational_space import OperationalSpaceController @configclass class OperationalSpaceControllerCfg: """Configuration for operational-space controller.""" - class_type: type = OperationalSpaceController + class_type: type[OperationalSpaceController] | str = "{DIR}.operational_space:OperationalSpaceController" """The associated controller class.""" target_types: Sequence[str] = MISSING diff --git a/source/isaaclab/isaaclab/devices/gamepad/se2_gamepad_cfg.py b/source/isaaclab/isaaclab/devices/gamepad/se2_gamepad_cfg.py index be6e2fa6c74..32bd60dea52 100644 --- a/source/isaaclab/isaaclab/devices/gamepad/se2_gamepad_cfg.py +++ b/source/isaaclab/isaaclab/devices/gamepad/se2_gamepad_cfg.py @@ -8,9 +8,12 @@ from __future__ import annotations from dataclasses import dataclass +from typing import TYPE_CHECKING from ..device_base import DeviceCfg -from .se2_gamepad import Se2Gamepad + +if TYPE_CHECKING: + from .se2_gamepad import Se2Gamepad @dataclass @@ -21,4 +24,4 @@ class Se2GamepadCfg(DeviceCfg): v_y_sensitivity: float = 1.0 omega_z_sensitivity: float = 1.0 dead_zone: float = 0.01 - class_type: type | str = Se2Gamepad + class_type: type[Se2Gamepad] | str = "{DIR}.se2_gamepad:Se2Gamepad" diff --git a/source/isaaclab/isaaclab/devices/gamepad/se3_gamepad_cfg.py b/source/isaaclab/isaaclab/devices/gamepad/se3_gamepad_cfg.py index f0da44bb8c5..3434a3ad113 100644 --- a/source/isaaclab/isaaclab/devices/gamepad/se3_gamepad_cfg.py +++ b/source/isaaclab/isaaclab/devices/gamepad/se3_gamepad_cfg.py @@ -8,9 +8,12 @@ from __future__ import annotations from dataclasses import dataclass +from typing import TYPE_CHECKING from ..device_base import DeviceCfg -from .se3_gamepad import Se3Gamepad + +if TYPE_CHECKING: + from .se3_gamepad import Se3Gamepad @dataclass @@ -21,4 +24,4 @@ class Se3GamepadCfg(DeviceCfg): dead_zone: float = 0.01 pos_sensitivity: float = 1.0 rot_sensitivity: float = 1.6 - class_type: type | str = Se3Gamepad + class_type: type[Se3Gamepad] | str = "{DIR}.se3_gamepad:Se3Gamepad" diff --git a/source/isaaclab/isaaclab/devices/keyboard/se2_keyboard_cfg.py b/source/isaaclab/isaaclab/devices/keyboard/se2_keyboard_cfg.py index 4bc47afd0fc..1a138e1683d 100644 --- a/source/isaaclab/isaaclab/devices/keyboard/se2_keyboard_cfg.py +++ b/source/isaaclab/isaaclab/devices/keyboard/se2_keyboard_cfg.py @@ -8,9 +8,12 @@ from __future__ import annotations from dataclasses import dataclass +from typing import TYPE_CHECKING from ..device_base import DeviceCfg -from .se2_keyboard import Se2Keyboard + +if TYPE_CHECKING: + from .se2_keyboard import Se2Keyboard @dataclass @@ -20,4 +23,4 @@ class Se2KeyboardCfg(DeviceCfg): v_x_sensitivity: float = 0.8 v_y_sensitivity: float = 0.4 omega_z_sensitivity: float = 1.0 - class_type: type | str = Se2Keyboard + class_type: type[Se2Keyboard] | str = "{DIR}.se2_keyboard:Se2Keyboard" diff --git a/source/isaaclab/isaaclab/devices/keyboard/se3_keyboard_cfg.py b/source/isaaclab/isaaclab/devices/keyboard/se3_keyboard_cfg.py index 015d60fc02b..36d6f48f1ae 100644 --- a/source/isaaclab/isaaclab/devices/keyboard/se3_keyboard_cfg.py +++ b/source/isaaclab/isaaclab/devices/keyboard/se3_keyboard_cfg.py @@ -8,9 +8,12 @@ from __future__ import annotations from dataclasses import dataclass +from typing import TYPE_CHECKING from ..device_base import DeviceCfg -from .se3_keyboard import Se3Keyboard + +if TYPE_CHECKING: + from .se3_keyboard import Se3Keyboard @dataclass @@ -21,4 +24,4 @@ class Se3KeyboardCfg(DeviceCfg): pos_sensitivity: float = 0.4 rot_sensitivity: float = 0.8 retargeters: None = None - class_type: type | str = Se3Keyboard + class_type: type[Se3Keyboard] | str = "{DIR}.se3_keyboard:Se3Keyboard" diff --git a/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse.py b/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse.py index d5ec067d4c1..07d26f66bd0 100644 --- a/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse.py +++ b/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse.py @@ -19,10 +19,10 @@ from isaaclab.utils.array import convert_to_torch from ..device_base import DeviceBase +from .utils import convert_buffer if TYPE_CHECKING: from .se2_spacemouse_cfg import Se2SpaceMouseCfg -from .utils import convert_buffer class Se2SpaceMouse(DeviceBase): diff --git a/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse_cfg.py b/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse_cfg.py index 511f2147f11..6cf5005fb76 100644 --- a/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse_cfg.py +++ b/source/isaaclab/isaaclab/devices/spacemouse/se2_spacemouse_cfg.py @@ -8,9 +8,12 @@ from __future__ import annotations from dataclasses import dataclass +from typing import TYPE_CHECKING from ..device_base import DeviceCfg -from .se2_spacemouse import Se2SpaceMouse + +if TYPE_CHECKING: + from .se2_spacemouse import Se2SpaceMouse @dataclass @@ -20,4 +23,4 @@ class Se2SpaceMouseCfg(DeviceCfg): v_x_sensitivity: float = 0.8 v_y_sensitivity: float = 0.4 omega_z_sensitivity: float = 1.0 - class_type: type | str = Se2SpaceMouse + class_type: type[Se2SpaceMouse] | str = "{DIR}.se2_spacemouse:Se2SpaceMouse" diff --git a/source/isaaclab/isaaclab/devices/spacemouse/se3_spacemouse_cfg.py b/source/isaaclab/isaaclab/devices/spacemouse/se3_spacemouse_cfg.py index 67955bffd65..0bf4b73b44f 100644 --- a/source/isaaclab/isaaclab/devices/spacemouse/se3_spacemouse_cfg.py +++ b/source/isaaclab/isaaclab/devices/spacemouse/se3_spacemouse_cfg.py @@ -8,9 +8,12 @@ from __future__ import annotations from dataclasses import dataclass +from typing import TYPE_CHECKING from ..device_base import DeviceCfg -from .se3_spacemouse import Se3SpaceMouse + +if TYPE_CHECKING: + from .se3_spacemouse import Se3SpaceMouse @dataclass @@ -21,4 +24,4 @@ class Se3SpaceMouseCfg(DeviceCfg): pos_sensitivity: float = 0.4 rot_sensitivity: float = 0.8 retargeters: None = None - class_type: type | str = Se3SpaceMouse + class_type: type[Se3SpaceMouse] | str = "{DIR}.se3_spacemouse:Se3SpaceMouse" diff --git a/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py b/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py index 684f786ba34..b22a6169d7a 100644 --- a/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/direct_marl_env_cfg.py @@ -17,7 +17,6 @@ from isaaclab.utils.noise import NoiseModelCfg from .common import AgentID, SpaceType, ViewerCfg -from .ui import BaseEnvWindow @configclass @@ -35,7 +34,7 @@ class DirectMARLEnvCfg: """Physics simulation configuration. Default is SimulationCfg().""" # ui settings - ui_window_class_type: type | None = BaseEnvWindow + ui_window_class_type: type | str | None = "isaaclab.envs.ui.base_env_window:BaseEnvWindow" """The class type of the UI window. Default is None. If None, then no UI window is created. diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py b/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py index 594e066c38b..fd40b3104c2 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env_cfg.py @@ -16,7 +16,6 @@ from isaaclab.utils.noise import NoiseModelCfg from .common import SpaceType, ViewerCfg -from .ui import BaseEnvWindow @configclass @@ -34,7 +33,7 @@ class DirectRLEnvCfg: """Physics simulation configuration. Default is SimulationCfg().""" # ui settings - ui_window_class_type: type | None = BaseEnvWindow + ui_window_class_type: type | str | None = "isaaclab.envs.ui.base_env_window:BaseEnvWindow" """The class type of the UI window. Default is None. If None, then no UI window is created. diff --git a/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py b/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py index 32a512aa6b4..24a88d5e72c 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env_cfg.py @@ -26,7 +26,6 @@ from isaaclab.utils import configclass from .common import ViewerCfg -from .ui import BaseEnvWindow @configclass @@ -52,7 +51,7 @@ class ManagerBasedEnvCfg: """Physics simulation configuration. Default is SimulationCfg().""" # ui settings - ui_window_class_type: type | None = BaseEnvWindow + ui_window_class_type: type | str | None = "isaaclab.envs.ui.base_env_window:BaseEnvWindow" """The class type of the UI window. Default is None. If None, then no UI window is created. diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py index 7fe29ed7003..102d4bc26cd 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env_cfg.py @@ -10,7 +10,6 @@ from isaaclab.utils import configclass from .manager_based_env_cfg import ManagerBasedEnvCfg -from .ui import ManagerBasedRLEnvWindow @configclass @@ -18,7 +17,7 @@ class ManagerBasedRLEnvCfg(ManagerBasedEnvCfg): """Configuration for a reinforcement learning environment with the manager-based workflow.""" # ui settings - ui_window_class_type: type | None = ManagerBasedRLEnvWindow + ui_window_class_type: type | str | None = "isaaclab.envs.ui.manager_based_rl_env_window:ManagerBasedRLEnvWindow" # general settings is_finite_horizon: bool = False diff --git a/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py b/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py index bb664445169..d86fe55ee43 100644 --- a/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py @@ -6,19 +6,19 @@ from __future__ import annotations from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.controllers import DifferentialIKControllerCfg, OperationalSpaceControllerCfg -from isaaclab.managers.action_manager import ActionTerm, ActionTermCfg +from isaaclab.managers.action_manager import ActionTermCfg from isaaclab.utils import configclass -from . import ( - binary_joint_actions, - joint_actions, - joint_actions_to_limits, - non_holonomic_actions, - surface_gripper_actions, - task_space_actions, -) +if TYPE_CHECKING: + from .binary_joint_actions import AbsBinaryJointPositionAction, BinaryJointPositionAction, BinaryJointVelocityAction + from .joint_actions import JointEffortAction, JointPositionAction, JointVelocityAction, RelativeJointPositionAction + from .joint_actions_to_limits import EMAJointPositionToLimitsAction, JointPositionToLimitsAction + from .non_holonomic_actions import NonHolonomicAction + from .surface_gripper_actions import SurfaceGripperBinaryAction + from .task_space_actions import DifferentialInverseKinematicsAction, OperationalSpaceControllerAction ## # Joint actions. @@ -49,7 +49,7 @@ class JointPositionActionCfg(JointActionCfg): See :class:`JointPositionAction` for more details. """ - class_type: type[ActionTerm] = joint_actions.JointPositionAction + class_type: type[JointPositionAction] | str = "{DIR}.joint_actions:JointPositionAction" use_default_offset: bool = True """Whether to use default joint positions configured in the articulation asset as offset. @@ -67,7 +67,7 @@ class RelativeJointPositionActionCfg(JointActionCfg): See :class:`RelativeJointPositionAction` for more details. """ - class_type: type[ActionTerm] = joint_actions.RelativeJointPositionAction + class_type: type[RelativeJointPositionAction] | str = "{DIR}.joint_actions:RelativeJointPositionAction" use_zero_offset: bool = True """Whether to ignore the offset defined in articulation asset. Defaults to True. @@ -83,7 +83,7 @@ class JointVelocityActionCfg(JointActionCfg): See :class:`JointVelocityAction` for more details. """ - class_type: type[ActionTerm] = joint_actions.JointVelocityAction + class_type: type[JointVelocityAction] | str = "{DIR}.joint_actions:JointVelocityAction" use_default_offset: bool = True """Whether to use default joint velocities configured in the articulation asset as offset. @@ -100,7 +100,7 @@ class JointEffortActionCfg(JointActionCfg): See :class:`JointEffortAction` for more details. """ - class_type: type[ActionTerm] = joint_actions.JointEffortAction + class_type: type[JointEffortAction] | str = "{DIR}.joint_actions:JointEffortAction" ## @@ -115,7 +115,7 @@ class JointPositionToLimitsActionCfg(ActionTermCfg): See :class:`JointPositionToLimitsAction` for more details. """ - class_type: type[ActionTerm] = joint_actions_to_limits.JointPositionToLimitsAction + class_type: type[JointPositionToLimitsAction] | str = "{DIR}.joint_actions_to_limits:JointPositionToLimitsAction" joint_names: list[str] = MISSING """List of joint names or regex expressions that the action will be mapped to.""" @@ -144,7 +144,9 @@ class EMAJointPositionToLimitsActionCfg(JointPositionToLimitsActionCfg): See :class:`EMAJointPositionToLimitsAction` for more details. """ - class_type: type[ActionTerm] = joint_actions_to_limits.EMAJointPositionToLimitsAction + class_type: type[EMAJointPositionToLimitsAction] | str = ( + "{DIR}.joint_actions_to_limits:EMAJointPositionToLimitsAction" + ) alpha: float | dict[str, float] = 1.0 """The weight for the moving average (float or dict of regex expressions). Defaults to 1.0. @@ -180,7 +182,7 @@ class BinaryJointPositionActionCfg(BinaryJointActionCfg): See :class:`BinaryJointPositionAction` for more details. """ - class_type: type[ActionTerm] = binary_joint_actions.BinaryJointPositionAction + class_type: type[BinaryJointPositionAction] | str = "{DIR}.binary_joint_actions:BinaryJointPositionAction" @configclass @@ -190,7 +192,7 @@ class BinaryJointVelocityActionCfg(BinaryJointActionCfg): See :class:`BinaryJointVelocityAction` for more details. """ - class_type: type[ActionTerm] = binary_joint_actions.BinaryJointVelocityAction + class_type: type[BinaryJointVelocityAction] | str = "{DIR}.binary_joint_actions:BinaryJointVelocityAction" @configclass @@ -225,7 +227,7 @@ class AbsBinaryJointPositionActionCfg(ActionTermCfg): positive_threshold: bool = True """Whether to use positive (Open actions > Close actions) threshold. Defaults to True.""" - class_type: type[ActionTerm] = binary_joint_actions.AbsBinaryJointPositionAction + class_type: type[AbsBinaryJointPositionAction] | str = "{DIR}.binary_joint_actions:AbsBinaryJointPositionAction" ## @@ -240,7 +242,7 @@ class NonHolonomicActionCfg(ActionTermCfg): See :class:`NonHolonomicAction` for more details. """ - class_type: type[ActionTerm] = non_holonomic_actions.NonHolonomicAction + class_type: type[NonHolonomicAction] | str = "{DIR}.non_holonomic_actions:NonHolonomicAction" body_name: str = MISSING """Name of the body which has the dummy mechanism connected to.""" @@ -283,7 +285,9 @@ class OffsetCfg: rot: tuple[float, float, float, float] = (0.0, 0.0, 0.0, 1.0) """Quaternion rotation ``(x, y, z, w)`` w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0, 1.0).""" - class_type: type[ActionTerm] = task_space_actions.DifferentialInverseKinematicsAction + class_type: type[DifferentialInverseKinematicsAction] | str = ( + "{DIR}.task_space_actions:DifferentialInverseKinematicsAction" + ) joint_names: list[str] = MISSING """List of joint names or regex expressions that the action will be mapped to.""" @@ -319,7 +323,9 @@ class OffsetCfg: rot: tuple[float, float, float, float] = (0.0, 0.0, 0.0, 1.0) """Quaternion rotation ``(x, y, z, w)`` w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0, 1.0).""" - class_type: type[ActionTerm] = task_space_actions.OperationalSpaceControllerAction + class_type: type[OperationalSpaceControllerAction] | str = ( + "{DIR}.task_space_actions:OperationalSpaceControllerAction" + ) joint_names: list[str] = MISSING """List of joint names or regex expressions that the action will be mapped to.""" @@ -378,4 +384,4 @@ class SurfaceGripperBinaryActionCfg(ActionTermCfg): close_command: float = 1.0 """The command value to close the gripper. Defaults to 1.0.""" - class_type: type[ActionTerm] = surface_gripper_actions.SurfaceGripperBinaryAction + class_type: type[SurfaceGripperBinaryAction] | str = "{DIR}.surface_gripper_actions:SurfaceGripperBinaryAction" diff --git a/source/isaaclab/isaaclab/envs/mdp/actions/pink_actions_cfg.py b/source/isaaclab/isaaclab/envs/mdp/actions/pink_actions_cfg.py index a82433be84c..b5910b64d0f 100644 --- a/source/isaaclab/isaaclab/envs/mdp/actions/pink_actions_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/actions/pink_actions_cfg.py @@ -4,12 +4,14 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.controllers.pink_ik import PinkIKControllerCfg -from isaaclab.managers.action_manager import ActionTerm, ActionTermCfg +from isaaclab.managers.action_manager import ActionTermCfg from isaaclab.utils import configclass -from . import pink_task_space_actions +if TYPE_CHECKING: + from .pink_task_space_actions import PinkInverseKinematicsAction @configclass @@ -20,7 +22,7 @@ class PinkInverseKinematicsActionCfg(ActionTermCfg): which is a inverse kinematics framework. """ - class_type: type[ActionTerm] = pink_task_space_actions.PinkInverseKinematicsAction + class_type: type["PinkInverseKinematicsAction"] | str = "{DIR}.pink_task_space_actions:PinkInverseKinematicsAction" """Specifies the action term class type for Pink inverse kinematics action.""" pink_controlled_joint_names: list[str] = MISSING diff --git a/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py b/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py index 6bc16f15513..5c5a7dac602 100644 --- a/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/actions/rmpflow_actions_cfg.py @@ -6,12 +6,14 @@ from __future__ import annotations from dataclasses import MISSING +from typing import TYPE_CHECKING -from isaaclab.controllers.rmp_flow import RmpFlowControllerCfg -from isaaclab.managers.action_manager import ActionTerm, ActionTermCfg +from isaaclab.controllers.rmp_flow_cfg import RmpFlowControllerCfg +from isaaclab.managers.action_manager import ActionTermCfg from isaaclab.utils import configclass -from . import rmpflow_task_space_actions +if TYPE_CHECKING: + from .rmpflow_task_space_actions import RMPFlowAction @configclass @@ -31,7 +33,7 @@ class OffsetCfg: rot: tuple[float, float, float, float] = (0.0, 0.0, 0.0, 1.0) """Quaternion rotation ``(x, y, z, w)`` w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0, 1.0).""" - class_type: type[ActionTerm] = rmpflow_task_space_actions.RMPFlowAction + class_type: type[RMPFlowAction] | str = "{DIR}.rmpflow_task_space_actions:RMPFlowAction" joint_names: list[str] = MISSING """List of joint names or regex expressions that the action will be mapped to.""" diff --git a/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py b/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py index 390980f3454..3af6b3e32eb 100644 --- a/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py @@ -5,23 +5,25 @@ import math from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.managers import CommandTermCfg from isaaclab.markers import VisualizationMarkersCfg from isaaclab.markers.config import BLUE_ARROW_X_MARKER_CFG, FRAME_MARKER_CFG, GREEN_ARROW_X_MARKER_CFG from isaaclab.utils import configclass -from .null_command import NullCommand -from .pose_2d_command import TerrainBasedPose2dCommand, UniformPose2dCommand -from .pose_command import UniformPoseCommand -from .velocity_command import NormalVelocityCommand, UniformVelocityCommand +if TYPE_CHECKING: + from .null_command import NullCommand + from .pose_2d_command import TerrainBasedPose2dCommand, UniformPose2dCommand + from .pose_command import UniformPoseCommand + from .velocity_command import NormalVelocityCommand, UniformVelocityCommand @configclass class NullCommandCfg(CommandTermCfg): """Configuration for the null command generator.""" - class_type: type = NullCommand + class_type: type["NullCommand"] | str = "{DIR}.null_command:NullCommand" def __post_init__(self): """Post initialization.""" @@ -33,7 +35,7 @@ def __post_init__(self): class UniformVelocityCommandCfg(CommandTermCfg): """Configuration for the uniform velocity command generator.""" - class_type: type = UniformVelocityCommand + class_type: type["UniformVelocityCommand"] | str = "{DIR}.velocity_command:UniformVelocityCommand" asset_name: str = MISSING """Name of the asset in the environment for which the commands are generated.""" @@ -100,7 +102,7 @@ class Ranges: class NormalVelocityCommandCfg(UniformVelocityCommandCfg): """Configuration for the normal velocity command generator.""" - class_type: type = NormalVelocityCommand + class_type: type["NormalVelocityCommand"] | str = "{DIR}.velocity_command:NormalVelocityCommand" heading_command: bool = False # --> we don't use heading command for normal velocity command. @configclass @@ -133,7 +135,7 @@ class Ranges: class UniformPoseCommandCfg(CommandTermCfg): """Configuration for uniform pose command generator.""" - class_type: type = UniformPoseCommand + class_type: type["UniformPoseCommand"] | str = "{DIR}.pose_command:UniformPoseCommand" asset_name: str = MISSING """Name of the asset in the environment for which the commands are generated.""" @@ -189,7 +191,7 @@ class Ranges: class UniformPose2dCommandCfg(CommandTermCfg): """Configuration for the uniform 2D-pose command generator.""" - class_type: type = UniformPose2dCommand + class_type: type["UniformPose2dCommand"] | str = "{DIR}.pose_2d_command:UniformPose2dCommand" asset_name: str = MISSING """Name of the asset in the environment for which the commands are generated.""" @@ -232,7 +234,7 @@ class Ranges: class TerrainBasedPose2dCommandCfg(UniformPose2dCommandCfg): """Configuration for the terrain-based position command generator.""" - class_type = TerrainBasedPose2dCommand + class_type: type["TerrainBasedPose2dCommand"] | str = "{DIR}.pose_2d_command:TerrainBasedPose2dCommand" @configclass class Ranges: diff --git a/source/isaaclab/isaaclab/envs/mdp/recorders/recorders_cfg.py b/source/isaaclab/isaaclab/envs/mdp/recorders/recorders_cfg.py index d67350d7f20..47350159105 100644 --- a/source/isaaclab/isaaclab/envs/mdp/recorders/recorders_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/recorders/recorders_cfg.py @@ -2,10 +2,19 @@ # All rights reserved. # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab.managers.recorder_manager import RecorderManagerBaseCfg, RecorderTerm, RecorderTermCfg +from typing import TYPE_CHECKING + +from isaaclab.managers.recorder_manager import RecorderManagerBaseCfg, RecorderTermCfg from isaaclab.utils import configclass -from . import recorders +if TYPE_CHECKING: + from .recorders import ( + InitialStateRecorder, + PostStepProcessedActionsRecorder, + PostStepStatesRecorder, + PreStepActionsRecorder, + PreStepFlatPolicyObservationsRecorder, + ) ## # State recorders. @@ -16,35 +25,37 @@ class InitialStateRecorderCfg(RecorderTermCfg): """Configuration for the initial state recorder term.""" - class_type: type[RecorderTerm] = recorders.InitialStateRecorder + class_type: type["InitialStateRecorder"] | str = "{DIR}.recorders:InitialStateRecorder" @configclass class PostStepStatesRecorderCfg(RecorderTermCfg): """Configuration for the step state recorder term.""" - class_type: type[RecorderTerm] = recorders.PostStepStatesRecorder + class_type: type["PostStepStatesRecorder"] | str = "{DIR}.recorders:PostStepStatesRecorder" @configclass class PreStepActionsRecorderCfg(RecorderTermCfg): """Configuration for the step action recorder term.""" - class_type: type[RecorderTerm] = recorders.PreStepActionsRecorder + class_type: type["PreStepActionsRecorder"] | str = "{DIR}.recorders:PreStepActionsRecorder" @configclass class PreStepFlatPolicyObservationsRecorderCfg(RecorderTermCfg): """Configuration for the step policy observation recorder term.""" - class_type: type[RecorderTerm] = recorders.PreStepFlatPolicyObservationsRecorder + class_type: type["PreStepFlatPolicyObservationsRecorder"] | str = ( + "{DIR}.recorders:PreStepFlatPolicyObservationsRecorder" + ) @configclass class PostStepProcessedActionsRecorderCfg(RecorderTermCfg): """Configuration for the post step processed actions recorder term.""" - class_type: type[RecorderTerm] = recorders.PostStepProcessedActionsRecorder + class_type: type["PostStepProcessedActionsRecorder"] | str = "{DIR}.recorders:PostStepProcessedActionsRecorder" ## diff --git a/source/isaaclab/isaaclab/envs/ui/base_env_window.py b/source/isaaclab/isaaclab/envs/ui/base_env_window.py index 26ea313d8d5..36b1c0fab1c 100644 --- a/source/isaaclab/isaaclab/envs/ui/base_env_window.py +++ b/source/isaaclab/isaaclab/envs/ui/base_env_window.py @@ -11,16 +11,16 @@ from datetime import datetime from typing import TYPE_CHECKING +from pxr import Sdf, Usd, UsdGeom, UsdPhysics + +from isaaclab.sim.utils.stage import resolve_paths from isaaclab.ui.widgets import ManagerLiveVisualizer from isaaclab.utils.version import has_kit if has_kit(): import isaacsim - import omni.kit.app import omni.kit.commands - from pxr import Sdf, Usd, UsdGeom, UsdPhysics - from isaaclab.sim.utils.stage import get_current_stage, resolve_paths if TYPE_CHECKING: import omni.ui @@ -64,7 +64,7 @@ def __init__(self, env: ManagerBasedEnv, window_name: str = "IsaacLab"): ] # get stage handle - self.stage = get_current_stage() + self.stage = env.sim.stage # Listeners for environment selection changes self._ui_listeners: list[ManagerLiveVisualizer] = [] diff --git a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py index 49e1c5a8ddd..1b5070cfd21 100644 --- a/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/camera_cfg.py @@ -6,7 +6,7 @@ from __future__ import annotations from dataclasses import MISSING, field -from typing import Literal +from typing import TYPE_CHECKING, Literal from isaaclab_physx.renderers import IsaacRtxRendererCfg @@ -15,7 +15,9 @@ from isaaclab.utils import configclass from ..sensor_base_cfg import SensorBaseCfg -from .camera import Camera + +if TYPE_CHECKING: + from .camera import Camera @configclass @@ -42,7 +44,7 @@ class OffsetCfg: """ - class_type: type = Camera + class_type: type[Camera] | str = "{DIR}.camera:Camera" offset: OffsetCfg = OffsetCfg() """The offset pose of the sensor's frame from the sensor's parent frame. Defaults to identity. diff --git a/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py b/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py index 2241a0648fd..c0613406ef3 100644 --- a/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/camera/tiled_camera_cfg.py @@ -3,14 +3,18 @@ # # SPDX-License-Identifier: BSD-3-Clause +from typing import TYPE_CHECKING + from isaaclab.utils import configclass from .camera_cfg import CameraCfg -from .tiled_camera import TiledCamera + +if TYPE_CHECKING: + from .tiled_camera import TiledCamera @configclass class TiledCameraCfg(CameraCfg): """Configuration for a tiled rendering-based camera sensor.""" - class_type: type = TiledCamera + class_type: type["TiledCamera"] | str = "{DIR}.tiled_camera:TiledCamera" diff --git a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor_cfg.py b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor_cfg.py index f1336eb325d..e6811774523 100644 --- a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor_cfg.py +++ b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor_cfg.py @@ -3,12 +3,16 @@ # # SPDX-License-Identifier: BSD-3-Clause +from typing import TYPE_CHECKING + from isaaclab.markers import VisualizationMarkersCfg from isaaclab.markers.config import CONTACT_SENSOR_MARKER_CFG from isaaclab.utils import configclass from ..sensor_base_cfg import SensorBaseCfg -from .contact_sensor import ContactSensor + +if TYPE_CHECKING: + from .contact_sensor import ContactSensor @configclass @@ -22,7 +26,7 @@ class ContactSensorCfg(SensorBaseCfg): see ``NewtonContactSensorCfg`` in ``isaaclab_newton``. """ - class_type: type = ContactSensor + class_type: type["ContactSensor"] | str = "{DIR}.contact_sensor:ContactSensor" track_pose: bool = False """Whether to track the pose of the sensor's origin. Defaults to False.""" diff --git a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py index 389f22c505c..b41c7d6d5f0 100644 --- a/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py +++ b/source/isaaclab/isaaclab/sensors/frame_transformer/frame_transformer_cfg.py @@ -6,12 +6,15 @@ from __future__ import annotations from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.markers.config import FRAME_MARKER_CFG, VisualizationMarkersCfg from isaaclab.utils import configclass from ..sensor_base_cfg import SensorBaseCfg -from .frame_transformer import FrameTransformer + +if TYPE_CHECKING: + from .frame_transformer import FrameTransformer @configclass @@ -54,7 +57,7 @@ class FrameCfg: offset: OffsetCfg = OffsetCfg() """The pose offset from the parent prim frame.""" - class_type: type = FrameTransformer + class_type: type[FrameTransformer] | str = "{DIR}.frame_transformer:FrameTransformer" prim_path: str = MISSING """The prim path of the body to transform from (source frame).""" diff --git a/source/isaaclab/isaaclab/sensors/imu/imu_cfg.py b/source/isaaclab/isaaclab/sensors/imu/imu_cfg.py index 46c0e68cbc7..3b3b6fb9f83 100644 --- a/source/isaaclab/isaaclab/sensors/imu/imu_cfg.py +++ b/source/isaaclab/isaaclab/sensors/imu/imu_cfg.py @@ -5,19 +5,23 @@ from __future__ import annotations +from typing import TYPE_CHECKING + from isaaclab.markers import VisualizationMarkersCfg from isaaclab.markers.config import RED_ARROW_X_MARKER_CFG from isaaclab.utils import configclass from ..sensor_base_cfg import SensorBaseCfg -from .imu import Imu + +if TYPE_CHECKING: + from .imu import Imu @configclass class ImuCfg(SensorBaseCfg): """Configuration for an Inertial Measurement Unit (IMU) sensor.""" - class_type: type = Imu + class_type: type[Imu] | str = "{DIR}.imu:Imu" @configclass class OffsetCfg: diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_camera_cfg.py b/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_camera_cfg.py index 45df51ce6d8..c625ccffedf 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_camera_cfg.py @@ -6,13 +6,16 @@ """Configuration for the ray-cast camera sensor.""" import logging +from typing import TYPE_CHECKING from isaaclab.utils import configclass -from .multi_mesh_ray_caster_camera import MultiMeshRayCasterCamera from .multi_mesh_ray_caster_cfg import MultiMeshRayCasterCfg from .ray_caster_camera_cfg import RayCasterCameraCfg +if TYPE_CHECKING: + from .multi_mesh_ray_caster_camera import MultiMeshRayCasterCamera + # import logger logger = logging.getLogger(__name__) @@ -21,7 +24,7 @@ class MultiMeshRayCasterCameraCfg(RayCasterCameraCfg, MultiMeshRayCasterCfg): """Configuration for the multi-mesh ray-cast camera sensor.""" - class_type: type = MultiMeshRayCasterCamera + class_type: type["MultiMeshRayCasterCamera"] | str = "{DIR}.multi_mesh_ray_caster_camera:MultiMeshRayCasterCamera" def __post_init__(self): super().__post_init__() diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_cfg.py b/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_cfg.py index f5393920162..3e7de9429c6 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_cfg.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster_cfg.py @@ -7,12 +7,15 @@ """Configuration for the ray-cast sensor.""" from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.utils import configclass -from .multi_mesh_ray_caster import MultiMeshRayCaster from .ray_caster_cfg import RayCasterCfg +if TYPE_CHECKING: + from .multi_mesh_ray_caster import MultiMeshRayCaster + @configclass class MultiMeshRayCasterCfg(RayCasterCfg): @@ -49,7 +52,7 @@ class RaycastTargetCfg: Not tracking the mesh transformations is recommended when the meshes are static to increase performance. """ - class_type: type = MultiMeshRayCaster + class_type: type["MultiMeshRayCaster"] | str = "{DIR}.multi_mesh_ray_caster:MultiMeshRayCaster" mesh_prim_paths: list[str | RaycastTargetCfg] = MISSING """The list of mesh primitive paths to ray cast against. diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera_cfg.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera_cfg.py index d8e43381708..98020d845f8 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera_cfg.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_camera_cfg.py @@ -6,14 +6,16 @@ """Configuration for the ray-cast camera sensor.""" from dataclasses import MISSING -from typing import Literal +from typing import TYPE_CHECKING, Literal from isaaclab.utils import configclass from .patterns import PinholeCameraPatternCfg -from .ray_caster_camera import RayCasterCamera from .ray_caster_cfg import RayCasterCfg +if TYPE_CHECKING: + from .ray_caster_camera import RayCasterCamera + @configclass class RayCasterCameraCfg(RayCasterCfg): @@ -39,7 +41,7 @@ class OffsetCfg: """ - class_type: type = RayCasterCamera + class_type: type["RayCasterCamera"] | str = "{DIR}.ray_caster_camera:RayCasterCamera" offset: OffsetCfg = OffsetCfg() """The offset pose of the sensor's frame from the sensor's parent frame. Defaults to identity.""" diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py index 23981b98ee9..7d91e446ada 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/ray_caster_cfg.py @@ -8,7 +8,7 @@ from __future__ import annotations from dataclasses import MISSING -from typing import Literal +from typing import TYPE_CHECKING, Literal from isaaclab.markers import VisualizationMarkersCfg from isaaclab.markers.config import RAY_CASTER_MARKER_CFG @@ -16,7 +16,9 @@ from ..sensor_base_cfg import SensorBaseCfg from .patterns.patterns_cfg import PatternBaseCfg -from .ray_caster import RayCaster + +if TYPE_CHECKING: + from .ray_caster import RayCaster @configclass @@ -32,7 +34,7 @@ class OffsetCfg: rot: tuple[float, float, float, float] = (0.0, 0.0, 0.0, 1.0) """Quaternion rotation (x, y, z, w) w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0, 1.0).""" - class_type: type = RayCaster + class_type: type[RayCaster] | str = "{DIR}.ray_caster:RayCaster" mesh_prim_paths: list[str] = MISSING """The list of mesh primitive paths to ray cast against. diff --git a/source/isaaclab/isaaclab/sensors/sensor_base.py b/source/isaaclab/isaaclab/sensors/sensor_base.py index af9b5554dee..8b317ef02c6 100644 --- a/source/isaaclab/isaaclab/sensors/sensor_base.py +++ b/source/isaaclab/isaaclab/sensors/sensor_base.py @@ -19,7 +19,6 @@ from typing import TYPE_CHECKING, Any import warp as wp -from isaaclab_physx.physics import IsaacEvents, PhysxManager import isaaclab.sim as sim_utils from isaaclab.physics import PhysicsEvent @@ -57,7 +56,6 @@ def __init__(self, cfg: SensorBaseCfg): self._is_initialized = False # flag for whether the sensor is in visualization mode self._is_visualizing = False - # get stage handle self.stage = get_current_stage() # register various callback functions @@ -287,6 +285,8 @@ def safe_callback(callback_name, event, obj_ref): # note: use weakref on callbacks to ensure that this object can be deleted when its destructor is called. obj_ref = weakref.proxy(self) + from isaaclab_physx.physics import IsaacEvents, PhysxManager # noqa: PLC0415 + # Register PHYSICS_READY callback for initialization (order=10 for lower priority) self._initialize_handle = PhysxManager.register_callback( lambda payload, obj_ref=obj_ref: safe_callback("_initialize_callback", payload, obj_ref), @@ -318,6 +318,8 @@ def _initialize_callback(self, event): self._is_initialized = True except Exception as e: # Store exception to be raised after callback completes + from isaaclab_physx.physics import PhysxManager # noqa: PLC0415 + PhysxManager.store_callback_exception(e) def _invalidate_initialize_callback(self, event): diff --git a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py index ad9f5585904..0de0b85911e 100644 --- a/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/from_files/from_files_cfg.py @@ -14,8 +14,6 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR -from . import from_files - @configclass class FileCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg): @@ -96,7 +94,7 @@ class UsdFileCfg(FileCfg): This is done by calling the respective function with the specified properties. """ - func: Callable = from_files.spawn_from_usd + func: Callable | str = "{DIR}.from_files:spawn_from_usd" usd_path: str = MISSING """Path to the USD file to spawn asset from.""" @@ -129,7 +127,7 @@ class UrdfFileCfg(FileCfg, converters.UrdfConverterCfg): """ - func: Callable = from_files.spawn_from_urdf + func: Callable | str = "{DIR}.from_files:spawn_from_urdf" @configclass @@ -151,7 +149,7 @@ class MjcfFileCfg(FileCfg, converters.MjcfConverterCfg): """ - func: Callable = from_files.spawn_from_mjcf + func: Callable | str = "{DIR}.from_files:spawn_from_mjcf" """ @@ -169,7 +167,7 @@ class UsdFileWithCompliantContactCfg(UsdFileCfg): material application. """ - func: Callable = from_files.spawn_from_usd_with_compliant_contact_material + func: Callable | str = "{DIR}.from_files:spawn_from_usd_with_compliant_contact_material" compliant_contact_stiffness: float | None = None """Stiffness of the compliant contact. Defaults to None. @@ -201,7 +199,7 @@ class GroundPlaneCfg(SpawnerCfg): This uses the USD for the standard grid-world ground plane from Isaac Sim by default. """ - func: Callable = from_files.spawn_ground_plane + func: Callable | str = "{DIR}.from_files:spawn_ground_plane" usd_path: str = f"{ISAAC_NUCLEUS_DIR}/Environments/Grid/default_environment.usd" """Path to the USD file to spawn asset from. Defaults to the grid-world ground plane.""" diff --git a/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py b/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py index 4768ffcba57..653e83a108c 100644 --- a/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/lights/lights_cfg.py @@ -12,8 +12,6 @@ from isaaclab.sim.spawners.spawner_cfg import SpawnerCfg from isaaclab.utils import configclass -from . import lights - @configclass class LightCfg(SpawnerCfg): @@ -26,7 +24,7 @@ class LightCfg(SpawnerCfg): The default values for the attributes are those specified in the their official documentation. """ - func: Callable = lights.spawn_light + func: Callable | str = "{DIR}.lights:spawn_light" prim_type: str = MISSING """The prim type name for the light prim.""" diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py index be63a9dd4a4..222ebd8ce28 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py @@ -11,8 +11,6 @@ from isaaclab.utils import configclass -from . import physics_materials - @configclass class PhysicsMaterialCfg: @@ -35,7 +33,7 @@ class RigidBodyMaterialCfg(PhysicsMaterialCfg): See :meth:`spawn_rigid_body_material` for more information. """ - func: Callable = physics_materials.spawn_rigid_body_material + func: Callable | str = "{DIR}.physics_materials:spawn_rigid_body_material" static_friction: float = 0.5 """The static friction coefficient. Defaults to 0.5.""" @@ -89,7 +87,7 @@ class DeformableBodyMaterialCfg(PhysicsMaterialCfg): """ - func: Callable = physics_materials.spawn_deformable_body_material + func: Callable | str = "{DIR}.physics_materials:spawn_deformable_body_material" density: float | None = None """The material density. Defaults to None, in which case the simulation decides the default density.""" diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py index 09e022c95cb..961b351b6ce 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/visual_materials_cfg.py @@ -10,8 +10,6 @@ from isaaclab.utils import configclass -from . import visual_materials - @configclass class VisualMaterialCfg: @@ -28,7 +26,7 @@ class PreviewSurfaceCfg(VisualMaterialCfg): See :meth:`spawn_preview_surface` for more information. """ - func: Callable = visual_materials.spawn_preview_surface + func: Callable | str = "{DIR}.visual_materials:spawn_preview_surface" diffuse_color: tuple[float, float, float] = (0.18, 0.18, 0.18) """The RGB diffusion color. This is the base color of the surface. Defaults to a dark gray.""" @@ -53,7 +51,7 @@ class MdlFileCfg(VisualMaterialCfg): See :meth:`spawn_from_mdl_file` for more information. """ - func: Callable = visual_materials.spawn_from_mdl_file + func: Callable | str = "{DIR}.visual_materials:spawn_from_mdl_file" mdl_path: str = MISSING """The path to the MDL material. @@ -95,7 +93,7 @@ class GlassMdlCfg(VisualMaterialCfg): The default values are taken from the glass material in the NVIDIA Nucleus. """ - func: Callable = visual_materials.spawn_from_mdl_file + func: Callable | str = "{DIR}.visual_materials:spawn_from_mdl_file" mdl_path: str = "OmniGlass.mdl" """The path to the MDL material. Defaults to the glass material in the NVIDIA Nucleus.""" diff --git a/source/isaaclab/isaaclab/sim/spawners/meshes/meshes_cfg.py b/source/isaaclab/isaaclab/sim/spawners/meshes/meshes_cfg.py index d5c39a505b8..9cf3d45716f 100644 --- a/source/isaaclab/isaaclab/sim/spawners/meshes/meshes_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/meshes/meshes_cfg.py @@ -13,8 +13,6 @@ from isaaclab.sim.spawners.spawner_cfg import DeformableObjectSpawnerCfg, RigidObjectSpawnerCfg from isaaclab.utils import configclass -from . import meshes - @configclass class MeshCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg): @@ -74,7 +72,7 @@ class MeshSphereCfg(MeshCfg): See :meth:`spawn_mesh_sphere` for more information. """ - func: Callable = meshes.spawn_mesh_sphere + func: Callable | str = "{DIR}.meshes:spawn_mesh_sphere" radius: float = MISSING """Radius of the sphere (in m).""" @@ -87,7 +85,7 @@ class MeshCuboidCfg(MeshCfg): See :meth:`spawn_mesh_cuboid` for more information. """ - func: Callable = meshes.spawn_mesh_cuboid + func: Callable | str = "{DIR}.meshes:spawn_mesh_cuboid" size: tuple[float, float, float] = MISSING """Size of the cuboid (in m).""" @@ -100,7 +98,7 @@ class MeshCylinderCfg(MeshCfg): See :meth:`spawn_cylinder` for more information. """ - func: Callable = meshes.spawn_mesh_cylinder + func: Callable | str = "{DIR}.meshes:spawn_mesh_cylinder" radius: float = MISSING """Radius of the cylinder (in m).""" @@ -117,7 +115,7 @@ class MeshCapsuleCfg(MeshCfg): See :meth:`spawn_capsule` for more information. """ - func: Callable = meshes.spawn_mesh_capsule + func: Callable | str = "{DIR}.meshes:spawn_mesh_capsule" radius: float = MISSING """Radius of the capsule (in m).""" @@ -134,7 +132,7 @@ class MeshConeCfg(MeshCfg): See :meth:`spawn_cone` for more information. """ - func: Callable = meshes.spawn_mesh_cone + func: Callable | str = "{DIR}.meshes:spawn_mesh_cone" radius: float = MISSING """Radius of the cone (in m).""" diff --git a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py index 44e5eb06173..56c9102cf1f 100644 --- a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py @@ -12,8 +12,6 @@ from isaaclab.sim.spawners.spawner_cfg import SpawnerCfg from isaaclab.utils import configclass -from . import sensors - @configclass class PinholeCameraCfg(SpawnerCfg): @@ -26,7 +24,7 @@ class PinholeCameraCfg(SpawnerCfg): world unit is Meter s.t. all of these values are set in cm. """ - func: Callable = sensors.spawn_camera + func: Callable | str = "{DIR}.sensors:spawn_camera" projection_type: str = "pinhole" """Type of projection to use for the camera. Defaults to "pinhole". @@ -172,7 +170,7 @@ class FisheyeCameraCfg(PinholeCameraCfg): .. _fish-eye camera: https://en.wikipedia.org/wiki/Fisheye_lens """ - func: Callable = sensors.spawn_camera + func: Callable | str = "{DIR}.sensors:spawn_camera" projection_type: Literal[ "fisheyePolynomial", diff --git a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py index 921b1ede29c..2baa75d19e6 100644 --- a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes_cfg.py @@ -13,8 +13,6 @@ from isaaclab.sim.spawners.spawner_cfg import RigidObjectSpawnerCfg from isaaclab.utils import configclass -from . import shapes - @configclass class ShapeCfg(RigidObjectSpawnerCfg): @@ -54,7 +52,7 @@ class SphereCfg(ShapeCfg): See :meth:`spawn_sphere` for more information. """ - func: Callable = shapes.spawn_sphere + func: Callable | str = "{DIR}.shapes:spawn_sphere" radius: float = MISSING """Radius of the sphere (in m).""" @@ -67,7 +65,7 @@ class CuboidCfg(ShapeCfg): See :meth:`spawn_cuboid` for more information. """ - func: Callable = shapes.spawn_cuboid + func: Callable | str = "{DIR}.shapes:spawn_cuboid" size: tuple[float, float, float] = MISSING """Size of the cuboid.""" @@ -80,7 +78,7 @@ class CylinderCfg(ShapeCfg): See :meth:`spawn_cylinder` for more information. """ - func: Callable = shapes.spawn_cylinder + func: Callable | str = "{DIR}.shapes:spawn_cylinder" radius: float = MISSING """Radius of the cylinder (in m).""" @@ -97,7 +95,7 @@ class CapsuleCfg(ShapeCfg): See :meth:`spawn_capsule` for more information. """ - func: Callable = shapes.spawn_capsule + func: Callable | str = "{DIR}.shapes:spawn_capsule" radius: float = MISSING """Radius of the capsule (in m).""" @@ -114,7 +112,7 @@ class ConeCfg(ShapeCfg): See :meth:`spawn_cone` for more information. """ - func: Callable = shapes.spawn_cone + func: Callable | str = "{DIR}.shapes:spawn_cone" radius: float = MISSING """Radius of the cone (in m).""" diff --git a/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py b/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py index d4ef0da9b60..ba86e4937fc 100644 --- a/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/spawner_cfg.py @@ -7,12 +7,15 @@ from collections.abc import Callable from dataclasses import MISSING +from typing import TYPE_CHECKING -from pxr import Usd - -from isaaclab.sim import schemas from isaaclab.utils import configclass +if TYPE_CHECKING: + from pxr import Usd + + from isaaclab.sim import schemas + @configclass class SpawnerCfg: diff --git a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py index f3d7b7986ec..1533c29687e 100644 --- a/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py @@ -9,8 +9,6 @@ from isaaclab.sim.spawners.spawner_cfg import DeformableObjectSpawnerCfg, RigidObjectSpawnerCfg, SpawnerCfg from isaaclab.utils import configclass -from . import wrappers - @configclass class MultiAssetSpawnerCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg): @@ -29,7 +27,7 @@ class MultiAssetSpawnerCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg): """ - func = wrappers.spawn_multi_asset + func: str = "{DIR}.wrappers:spawn_multi_asset" assets_cfg: list[SpawnerCfg] = MISSING """List of asset configurations to spawn.""" @@ -57,7 +55,7 @@ class MultiUsdFileCfg(UsdFileCfg): """ - func = wrappers.spawn_multi_usd_file + func: str = "{DIR}.wrappers:spawn_multi_usd_file" usd_path: str | list[str] = MISSING """Path or a list of paths to the USD files to spawn asset from.""" diff --git a/source/isaaclab/isaaclab/terrains/height_field/hf_terrains_cfg.py b/source/isaaclab/isaaclab/terrains/height_field/hf_terrains_cfg.py index df1d6dcc21a..069f87503e6 100644 --- a/source/isaaclab/isaaclab/terrains/height_field/hf_terrains_cfg.py +++ b/source/isaaclab/isaaclab/terrains/height_field/hf_terrains_cfg.py @@ -8,7 +8,6 @@ from isaaclab.utils import configclass from ..sub_terrain_cfg import SubTerrainBaseCfg -from . import hf_terrains @configclass @@ -42,7 +41,7 @@ class HfTerrainBaseCfg(SubTerrainBaseCfg): class HfRandomUniformTerrainCfg(HfTerrainBaseCfg): """Configuration for a random uniform height field terrain.""" - function = hf_terrains.random_uniform_terrain + function: str = "{DIR}.hf_terrains:random_uniform_terrain" noise_range: tuple[float, float] = MISSING """The minimum and maximum height noise (i.e. along z) of the terrain (in m).""" @@ -63,7 +62,7 @@ class HfRandomUniformTerrainCfg(HfTerrainBaseCfg): class HfPyramidSlopedTerrainCfg(HfTerrainBaseCfg): """Configuration for a pyramid sloped height field terrain.""" - function = hf_terrains.pyramid_sloped_terrain + function: str = "{DIR}.hf_terrains:pyramid_sloped_terrain" slope_range: tuple[float, float] = MISSING """The slope of the terrain (in radians).""" @@ -95,7 +94,7 @@ class HfInvertedPyramidSlopedTerrainCfg(HfPyramidSlopedTerrainCfg): class HfPyramidStairsTerrainCfg(HfTerrainBaseCfg): """Configuration for a pyramid stairs height field terrain.""" - function = hf_terrains.pyramid_stairs_terrain + function: str = "{DIR}.hf_terrains:pyramid_stairs_terrain" step_height_range: tuple[float, float] = MISSING """The minimum and maximum height of the steps (in m).""" @@ -130,7 +129,7 @@ class HfInvertedPyramidStairsTerrainCfg(HfPyramidStairsTerrainCfg): class HfDiscreteObstaclesTerrainCfg(HfTerrainBaseCfg): """Configuration for a discrete obstacles height field terrain.""" - function = hf_terrains.discrete_obstacles_terrain + function: str = "{DIR}.hf_terrains:discrete_obstacles_terrain" obstacle_height_mode: str = "choice" """The mode to use for the obstacle height. Defaults to "choice". @@ -155,7 +154,7 @@ class HfDiscreteObstaclesTerrainCfg(HfTerrainBaseCfg): class HfWaveTerrainCfg(HfTerrainBaseCfg): """Configuration for a wave height field terrain.""" - function = hf_terrains.wave_terrain + function: str = "{DIR}.hf_terrains:wave_terrain" amplitude_range: tuple[float, float] = MISSING """The minimum and maximum amplitude of the wave (in m).""" @@ -168,7 +167,7 @@ class HfWaveTerrainCfg(HfTerrainBaseCfg): class HfSteppingStonesTerrainCfg(HfTerrainBaseCfg): """Configuration for a stepping stones height field terrain.""" - function = hf_terrains.stepping_stones_terrain + function: str = "{DIR}.hf_terrains:stepping_stones_terrain" stone_height_max: float = MISSING """The maximum height of the stones (in m).""" diff --git a/source/isaaclab/isaaclab/terrains/terrain_generator_cfg.py b/source/isaaclab/isaaclab/terrains/terrain_generator_cfg.py index 6a3238c7cb4..605b8116e7d 100644 --- a/source/isaaclab/isaaclab/terrains/terrain_generator_cfg.py +++ b/source/isaaclab/isaaclab/terrains/terrain_generator_cfg.py @@ -15,19 +15,21 @@ from __future__ import annotations from dataclasses import MISSING -from typing import Literal +from typing import TYPE_CHECKING, Literal from isaaclab.utils import configclass from .sub_terrain_cfg import SubTerrainBaseCfg -from .terrain_generator import TerrainGenerator + +if TYPE_CHECKING: + from .terrain_generator import TerrainGenerator @configclass class TerrainGeneratorCfg: """Configuration for the terrain generator.""" - class_type: type = TerrainGenerator + class_type: type[TerrainGenerator] | str = "{DIR}.terrain_generator:TerrainGenerator" """The class to use for the terrain generator. Defaults to :class:`isaaclab.terrains.terrain_generator.TerrainGenerator`. diff --git a/source/isaaclab/isaaclab/terrains/terrain_importer_cfg.py b/source/isaaclab/isaaclab/terrains/terrain_importer_cfg.py index 7b42e06caaf..279c4c981eb 100644 --- a/source/isaaclab/isaaclab/terrains/terrain_importer_cfg.py +++ b/source/isaaclab/isaaclab/terrains/terrain_importer_cfg.py @@ -11,17 +11,16 @@ import isaaclab.sim as sim_utils from isaaclab.utils import configclass -from .terrain_importer import TerrainImporter - if TYPE_CHECKING: from .terrain_generator_cfg import TerrainGeneratorCfg + from .terrain_importer import TerrainImporter @configclass class TerrainImporterCfg: """Configuration for the terrain manager.""" - class_type: type = TerrainImporter + class_type: type[TerrainImporter] | str = "{DIR}.terrain_importer:TerrainImporter" """The class to use for the terrain importer. Defaults to :class:`isaaclab.terrains.terrain_importer.TerrainImporter`. diff --git a/source/isaaclab/isaaclab/terrains/trimesh/mesh_terrains_cfg.py b/source/isaaclab/isaaclab/terrains/trimesh/mesh_terrains_cfg.py index 4247e21486b..1e82a88aee7 100644 --- a/source/isaaclab/isaaclab/terrains/trimesh/mesh_terrains_cfg.py +++ b/source/isaaclab/isaaclab/terrains/trimesh/mesh_terrains_cfg.py @@ -7,8 +7,6 @@ from dataclasses import MISSING from typing import Literal -import isaaclab.terrains.trimesh.mesh_terrains as mesh_terrains -import isaaclab.terrains.trimesh.utils as mesh_utils_terrains from isaaclab.utils import configclass from ..sub_terrain_cfg import SubTerrainBaseCfg @@ -22,14 +20,14 @@ class MeshPlaneTerrainCfg(SubTerrainBaseCfg): """Configuration for a plane mesh terrain.""" - function = mesh_terrains.flat_terrain + function: str = "{DIR}.mesh_terrains:flat_terrain" @configclass class MeshPyramidStairsTerrainCfg(SubTerrainBaseCfg): """Configuration for a pyramid stair mesh terrain.""" - function = mesh_terrains.pyramid_stairs_terrain + function: str = "{DIR}.mesh_terrains:pyramid_stairs_terrain" border_width: float = 0.0 """The width of the border around the terrain (in m). Defaults to 0.0. @@ -63,14 +61,14 @@ class MeshInvertedPyramidStairsTerrainCfg(MeshPyramidStairsTerrainCfg): This is the same as :class:`MeshPyramidStairsTerrainCfg` except that the steps are inverted. """ - function = mesh_terrains.inverted_pyramid_stairs_terrain + function: str = "{DIR}.mesh_terrains:inverted_pyramid_stairs_terrain" @configclass class MeshRandomGridTerrainCfg(SubTerrainBaseCfg): """Configuration for a random grid mesh terrain.""" - function = mesh_terrains.random_grid_terrain + function: str = "{DIR}.mesh_terrains:random_grid_terrain" grid_width: float = MISSING """The width of the grid cells (in m).""" @@ -93,7 +91,7 @@ class MeshRandomGridTerrainCfg(SubTerrainBaseCfg): class MeshRailsTerrainCfg(SubTerrainBaseCfg): """Configuration for a terrain with box rails as extrusions.""" - function = mesh_terrains.rails_terrain + function: str = "{DIR}.mesh_terrains:rails_terrain" rail_thickness_range: tuple[float, float] = MISSING """The thickness of the inner and outer rails (in m).""" @@ -109,7 +107,7 @@ class MeshRailsTerrainCfg(SubTerrainBaseCfg): class MeshPitTerrainCfg(SubTerrainBaseCfg): """Configuration for a terrain with a pit that leads out of the pit.""" - function = mesh_terrains.pit_terrain + function: str = "{DIR}.mesh_terrains:pit_terrain" pit_depth_range: tuple[float, float] = MISSING """The minimum and maximum height of the pit (in m).""" @@ -125,7 +123,7 @@ class MeshPitTerrainCfg(SubTerrainBaseCfg): class MeshBoxTerrainCfg(SubTerrainBaseCfg): """Configuration for a terrain with boxes (similar to a pyramid).""" - function = mesh_terrains.box_terrain + function: str = "{DIR}.mesh_terrains:box_terrain" box_height_range: tuple[float, float] = MISSING """The minimum and maximum height of the box (in m).""" @@ -141,7 +139,7 @@ class MeshBoxTerrainCfg(SubTerrainBaseCfg): class MeshGapTerrainCfg(SubTerrainBaseCfg): """Configuration for a terrain with a gap around the platform.""" - function = mesh_terrains.gap_terrain + function: str = "{DIR}.mesh_terrains:gap_terrain" gap_width_range: tuple[float, float] = MISSING """The minimum and maximum width of the gap (in m).""" @@ -154,7 +152,7 @@ class MeshGapTerrainCfg(SubTerrainBaseCfg): class MeshFloatingRingTerrainCfg(SubTerrainBaseCfg): """Configuration for a terrain with a floating ring around the center.""" - function = mesh_terrains.floating_ring_terrain + function: str = "{DIR}.mesh_terrains:floating_ring_terrain" ring_width_range: tuple[float, float] = MISSING """The minimum and maximum width of the ring (in m).""" @@ -173,7 +171,7 @@ class MeshFloatingRingTerrainCfg(SubTerrainBaseCfg): class MeshStarTerrainCfg(SubTerrainBaseCfg): """Configuration for a terrain with a star pattern.""" - function = mesh_terrains.star_terrain + function: str = "{DIR}.mesh_terrains:star_terrain" num_bars: int = MISSING """The number of bars per-side the star. Must be greater than 2.""" @@ -201,7 +199,7 @@ class ObjectCfg: height: float = MISSING """The height (along z) of the object (in m).""" - function = mesh_terrains.repeated_objects_terrain + function: str = "{DIR}.mesh_terrains:repeated_objects_terrain" object_type: Literal["cylinder", "box", "cone"] | callable = MISSING """The type of object to generate. @@ -263,7 +261,7 @@ class ObjectCfg(MeshRepeatedObjectsTerrainCfg.ObjectCfg): degrees: bool = True """Whether the angle is in degrees. Defaults to True.""" - object_type = mesh_utils_terrains.make_cone + object_type: str = "{DIR}.utils:make_cone" object_params_start: ObjectCfg = MISSING """The object curriculum parameters at the start of the curriculum.""" @@ -287,7 +285,7 @@ class ObjectCfg(MeshRepeatedObjectsTerrainCfg.ObjectCfg): degrees: bool = True """Whether the angle is in degrees. Defaults to True.""" - object_type = mesh_utils_terrains.make_box + object_type: str = "{DIR}.utils:make_box" object_params_start: ObjectCfg = MISSING """The box curriculum parameters at the start of the curriculum.""" @@ -311,7 +309,7 @@ class ObjectCfg(MeshRepeatedObjectsTerrainCfg.ObjectCfg): degrees: bool = True """Whether the angle is in degrees. Defaults to True.""" - object_type = mesh_utils_terrains.make_cylinder + object_type: str = "{DIR}.utils:make_cylinder" object_params_start: ObjectCfg = MISSING """The box curriculum parameters at the start of the curriculum.""" diff --git a/source/isaaclab/isaaclab/utils/configclass.py b/source/isaaclab/isaaclab/utils/configclass.py index e46280a61cc..fc119247ee9 100644 --- a/source/isaaclab/isaaclab/utils/configclass.py +++ b/source/isaaclab/isaaclab/utils/configclass.py @@ -6,6 +6,7 @@ """Sub-module that provides a wrapper around the Python 3.7 onwards ``dataclasses`` module.""" import inspect +import re import types from collections.abc import Callable from copy import deepcopy @@ -13,6 +14,10 @@ from typing import Any, ClassVar from .dict import class_to_dict, update_class_from_dict +from .string import ResolvableString + +_CALLABLE_STR_RE = re.compile(r"^[A-Za-z_][A-Za-z0-9_\\.]*:[A-Za-z_][A-Za-z0-9_]*$") +_CALLABLE_STR_WITH_DIR_RE = re.compile(r"^\{DIR\}(?:\.[A-Za-z_][A-Za-z0-9_]*)*:[A-Za-z_][A-Za-z0-9_]*$") _CONFIGCLASS_METHODS = ["to_dict", "from_dict", "replace", "copy", "validate"] """List of class methods added at runtime to dataclass.""" @@ -174,6 +179,42 @@ def _copy_class(obj: object) -> object: return replace(obj) +def _field_module_dir(obj: Any, key: str | None = None) -> str | None: + """Return module parent package path for an object or one of its declared fields.""" + cls = type(obj) + if key is not None: + # Use nearest declaration in MRO (subclass override wins). + for mro_cls in cls.__mro__: + if mro_cls is object: + continue + if key in mro_cls.__dict__: + cls = mro_cls + break + module_name = getattr(cls, "__module__", "") + return module_name.rsplit(".", 1)[0] if "." in module_name else (module_name or None) + + +def _wrap_resolvable_strings(value: Any, module_dir: str | None = None) -> Any: + """Recursively wrap callable-like strings with :class:`ResolvableString`.""" + if isinstance(value, str) and (_CALLABLE_STR_RE.match(value) or _CALLABLE_STR_WITH_DIR_RE.match(value)): + if "{DIR}" in value: + if module_dir is None: + raise ValueError(f"Cannot resolve '{{DIR}}' in '{value}' because no module context is available.") + value = value.replace("{DIR}", module_dir) + return ResolvableString(value) + if isinstance(value, list): + return [_wrap_resolvable_strings(item, module_dir=module_dir) for item in value] + if isinstance(value, tuple): + return tuple(_wrap_resolvable_strings(item, module_dir=module_dir) for item in value) + if isinstance(value, dict): + return {key: _wrap_resolvable_strings(item, module_dir=module_dir) for key, item in value.items()} + if hasattr(value, "__dataclass_fields__") and hasattr(value, "__dict__"): + for key, item in value.__dict__.items(): + nested_module_dir = _field_module_dir(value, key) + setattr(value, key, _wrap_resolvable_strings(item, module_dir=nested_module_dir)) + return value + + """ Private helper functions. """ @@ -399,7 +440,8 @@ def _custom_post_init(obj): ann = obj.__class__.__dict__.get(key) # duplicate data members that are mutable if not callable(value) and not isinstance(ann, property): - setattr(obj, key, deepcopy(value)) + copied_value = deepcopy(value) + setattr(obj, key, _wrap_resolvable_strings(copied_value, module_dir=_field_module_dir(obj, key))) def _combined_function(f1: Callable, f2: Callable) -> Callable: diff --git a/source/isaaclab/isaaclab/utils/dict.py b/source/isaaclab/isaaclab/utils/dict.py index de2062d6697..b80bcde6351 100644 --- a/source/isaaclab/isaaclab/utils/dict.py +++ b/source/isaaclab/isaaclab/utils/dict.py @@ -14,7 +14,7 @@ import torch from .array import TENSOR_TYPE_CONVERSIONS, TENSOR_TYPES -from .string import callable_to_string, string_to_callable, string_to_slice +from .string import ResolvableString, callable_to_string, string_to_slice """ Dictionary <-> Class operations. @@ -58,8 +58,12 @@ def class_to_dict(obj: object) -> dict[str, Any]: # disregard builtin attributes if key.startswith("__"): continue + # Keep lazy callable references as strings; don't force callable introspection. + if isinstance(value, ResolvableString): + data[key] = str(value) # check if attribute is callable -- function - if callable(value): + # check if attribute is callable -- function + elif callable(value): data[key] = callable_to_string(value) # check if attribute is a dictionary elif hasattr(value, "__dict__") or isinstance(value, dict): @@ -140,10 +144,17 @@ def update_class_from_dict(obj, data: dict[str, Any], _ns: str = "") -> None: if not set_obj: continue - # -- 3) callable attribute → resolve string -------------- + # -- 3) callable attribute → keep string lazily resolvable -------------- elif callable(obj_mem): - # update function name - value = string_to_callable(value) + # Do not eagerly import backend modules while applying config dictionaries. + # Keep callable strings lazy; they resolve only when actually invoked. + if isinstance(value, str) and not isinstance(value, ResolvableString): + value = ResolvableString(value) + elif not callable(value): + raise ValueError( + f"[Config]: Incorrect type under namespace: {key_ns}." + f" Expected callable or callable-string, Received: {type(value)}." + ) # -- 4) simple scalar / explicit None --------------------- elif value is None or isinstance(value, type(obj_mem)): diff --git a/source/isaaclab/isaaclab/utils/noise/noise_cfg.py b/source/isaaclab/isaaclab/utils/noise/noise_cfg.py index b3275643fd2..4265a12cda8 100644 --- a/source/isaaclab/isaaclab/utils/noise/noise_cfg.py +++ b/source/isaaclab/isaaclab/utils/noise/noise_cfg.py @@ -7,13 +7,14 @@ from collections.abc import Callable from dataclasses import MISSING -from typing import Literal +from typing import TYPE_CHECKING, Literal import torch from isaaclab.utils import configclass -from . import noise_model +if TYPE_CHECKING: + from .noise_model import NoiseModel, NoiseModelWithAdditiveBias @configclass @@ -34,7 +35,7 @@ class NoiseCfg: class ConstantNoiseCfg(NoiseCfg): """Configuration for an additive constant noise term.""" - func = noise_model.constant_noise + func: str = "{DIR}.noise_model:constant_noise" bias: torch.Tensor | float = 0.0 """The bias to add. Defaults to 0.0.""" @@ -44,7 +45,7 @@ class ConstantNoiseCfg(NoiseCfg): class UniformNoiseCfg(NoiseCfg): """Configuration for a additive uniform noise term.""" - func = noise_model.uniform_noise + func: str = "{DIR}.noise_model:uniform_noise" n_min: torch.Tensor | float = -1.0 """The minimum value of the noise. Defaults to -1.0.""" @@ -56,7 +57,7 @@ class UniformNoiseCfg(NoiseCfg): class GaussianNoiseCfg(NoiseCfg): """Configuration for an additive gaussian noise term.""" - func = noise_model.gaussian_noise + func: str = "{DIR}.noise_model:gaussian_noise" mean: torch.Tensor | float = 0.0 """The mean of the noise. Defaults to 0.0.""" @@ -73,7 +74,7 @@ class GaussianNoiseCfg(NoiseCfg): class NoiseModelCfg: """Configuration for a noise model.""" - class_type: type = noise_model.NoiseModel + class_type: type[NoiseModel] | str = "{DIR}.noise_model:NoiseModel" """The class type of the noise model.""" noise_cfg: NoiseCfg = MISSING @@ -97,7 +98,7 @@ class NoiseModelCfg: class NoiseModelWithAdditiveBiasCfg(NoiseModelCfg): """Configuration for an additive gaussian noise with bias model.""" - class_type: type = noise_model.NoiseModelWithAdditiveBias + class_type: type[NoiseModelWithAdditiveBias] | str = "{DIR}.noise_model:NoiseModelWithAdditiveBias" bias_noise_cfg: NoiseCfg = MISSING """The noise configuration for the bias. diff --git a/source/isaaclab/isaaclab/utils/string.py b/source/isaaclab/isaaclab/utils/string.py index dc1cdaf5347..8506da84819 100644 --- a/source/isaaclab/isaaclab/utils/string.py +++ b/source/isaaclab/isaaclab/utils/string.py @@ -170,6 +170,76 @@ def string_to_callable(name: str) -> Callable: raise ValueError(msg) +class ResolvableString(str): + """String subtype that lazily resolves ``module.path:Callable`` values. + + The object stays string-compatible for serialization and display, while also allowing callable + use and attribute access on the resolved callable/class. + """ + + __slots__ = ("_resolved_callable", "_resolve_error") + + def __new__(cls, value: str): + obj = super().__new__(cls, value) + obj._resolved_callable = None + obj._resolve_error = None + return obj + + def _resolve(self) -> Callable: + if self._resolved_callable is not None: + return self._resolved_callable + if self._resolve_error is not None: + raise self._resolve_error + try: + resolved = string_to_callable(str(self)) + except (ImportError, AttributeError, ValueError) as error: + self._resolve_error = error + raise + self._resolved_callable = resolved + return resolved + + def __call__(self, *args, **kwargs): + return self._resolve()(*args, **kwargs) + + def _split_ref(self) -> tuple[str | None, str]: + """Parse ``module:attribute`` reference without importing.""" + value = str(self) + if ":" not in value: + return None, value + module_name, attr_path = value.split(":", 1) + return module_name, attr_path + + def __getattribute__(self, item: str): + # Provide callable metadata without forcing import/resolution. + if item == "__name__": + _, attr_path = object.__getattribute__(self, "_split_ref")() + return attr_path.rsplit(".", 1)[-1] + if item == "__qualname__": + _, attr_path = object.__getattribute__(self, "_split_ref")() + return attr_path + if item == "__module__": + module_name, _ = object.__getattribute__(self, "_split_ref")() + if module_name is None: + return str.__module__ + return module_name + return super().__getattribute__(item) + + def __getattr__(self, item: str): + # Keep generic dunder probing (e.g. hasattr(..., "__dataclass_fields__")) + # lazy and side-effect free. Metadata dunders are handled in __getattribute__. + if item.startswith("__") and item.endswith("__"): + raise AttributeError(item) + return getattr(self._resolve(), item) + + def __copy__(self): + """Return self because strings are immutable.""" + return self + + def __deepcopy__(self, memo): + """Return self so deepcopy doesn't trigger lazy resolution.""" + return self + + """ Regex operations. """ diff --git a/source/isaaclab/test/utils/test_dict.py b/source/isaaclab/test/utils/test_dict.py index 35ce35f2657..2632bf5f55e 100644 --- a/source/isaaclab/test/utils/test_dict.py +++ b/source/isaaclab/test/utils/test_dict.py @@ -16,7 +16,10 @@ import random +import pytest + import isaaclab.utils.dict as dict_utils +import isaaclab.utils.string as string_utils def _test_function(x): @@ -97,3 +100,28 @@ def test_dict_to_md5(): for _ in range(200): md5_hash_2 = dict_utils.dict_to_md5_hash(test_dict) assert md5_hash_1 == md5_hash_2 + + +class _CallableCfg: + class_type = _test_function + + +def test_update_class_from_dict_keeps_callable_string_lazy(): + """Callable-string updates should remain lazy via ResolvableString.""" + cfg = _CallableCfg() + dict_utils.update_class_from_dict(cfg, {"class_type": "math:sin"}) + + assert isinstance(cfg.class_type, string_utils.ResolvableString) + # Dunder probing should not force resolution/import side effects. + assert hasattr(cfg.class_type, "__dataclass_fields__") is False + # Runtime use still resolves correctly. + assert pytest.approx(cfg.class_type(0.0), rel=0.0, abs=1e-9) == 0.0 + + +def test_update_class_from_dict_does_not_rewrap_resolvable_string(): + """Existing ResolvableString should be preserved, not re-wrapped.""" + cfg = _CallableCfg() + existing = string_utils.ResolvableString("math:sin") + dict_utils.update_class_from_dict(cfg, {"class_type": existing}) + + assert cfg.class_type is existing diff --git a/source/isaaclab/test/utils/test_string.py b/source/isaaclab/test/utils/test_string.py index d171a3885e1..ce443dec705 100644 --- a/source/isaaclab/test/utils/test_string.py +++ b/source/isaaclab/test/utils/test_string.py @@ -21,6 +21,44 @@ import isaaclab.utils.string as string_utils +def test_resolvable_string_metadata_is_non_eager(): + """Test metadata access on ResolvableString without triggering import/resolve.""" + ref = string_utils.ResolvableString("package.subpkg.module:Outer.InnerCallable") + assert ref.__module__ == "package.subpkg.module" + assert ref.__qualname__ == "Outer.InnerCallable" + assert ref.__name__ == "InnerCallable" + + +def test_resolvable_string_metadata_stable_after_resolution(): + """Test metadata before/after resolution remains consistent.""" + ref = string_utils.ResolvableString("math:sin") + assert ref.__module__ == "math" + assert ref.__qualname__ == "sin" + assert ref.__name__ == "sin" + # Force resolution. + assert pytest.approx(ref(0.0), rel=0.0, abs=1e-9) == 0.0 + # Metadata should remain identical after resolution cache is populated. + assert ref.__module__ == "math" + assert ref.__qualname__ == "sin" + assert ref.__name__ == "sin" + + +def test_resolvable_string_dunder_introspection_stays_lazy(): + """Test dunder probing doesn't force resolution for invalid references.""" + ref = string_utils.ResolvableString("not_a_real_module.path:Nope") + # dunder attribute probe should not attempt import/resolve + assert hasattr(ref, "__dataclass_fields__") is False + # runtime use should still attempt resolve and fail + with pytest.raises(ValueError): + ref() + + +def test_resolvable_string_runtime_resolution_still_works(): + """Test runtime call path still resolves the callable target.""" + ref = string_utils.ResolvableString("math:sin") + assert pytest.approx(ref(0.0), rel=0.0, abs=1e-9) == 0.0 + + def test_case_conversion(): """Test case conversion between camel case and snake case.""" # test camel case to snake case diff --git a/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster_cfg.py index 29072f421ab..1c20492fc2c 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster_cfg.py +++ b/source/isaaclab_contrib/isaaclab_contrib/actuators/thruster_cfg.py @@ -4,11 +4,12 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING -from typing import Literal +from typing import TYPE_CHECKING, Literal from isaaclab.utils import configclass -from .thruster import Thruster +if TYPE_CHECKING: + from .thruster import Thruster @configclass @@ -21,7 +22,7 @@ class ThrusterCfg: and must be provided by the user configuration. """ - class_type: type[Thruster] = Thruster + class_type: type["Thruster"] | str = "{DIR}.thruster:Thruster" """Concrete Python class that consumes this config.""" dt: float = MISSING diff --git a/source/isaaclab_contrib/isaaclab_contrib/assets/multirotor/multirotor_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/assets/multirotor/multirotor_cfg.py index 9638fcf2aa6..0a8538cc14f 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/assets/multirotor/multirotor_cfg.py +++ b/source/isaaclab_contrib/isaaclab_contrib/assets/multirotor/multirotor_cfg.py @@ -5,13 +5,15 @@ from collections.abc import Sequence from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.assets.articulation import ArticulationCfg from isaaclab.utils import configclass from isaaclab_contrib.actuators import ThrusterCfg -from .multirotor import Multirotor +if TYPE_CHECKING: + from .multirotor import Multirotor @configclass @@ -78,7 +80,7 @@ class MultirotorCfg(ArticulationCfg): - :class:`Multirotor`: Multirotor asset class """ - class_type: type = Multirotor + class_type: type["Multirotor"] | str = "{DIR}.multirotor:Multirotor" @configclass class InitialStateCfg(ArticulationCfg.InitialStateCfg): diff --git a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py index 0f457fe4a5a..3a464b8fce8 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py +++ b/source/isaaclab_contrib/isaaclab_contrib/mdp/actions/thrust_actions_cfg.py @@ -4,11 +4,13 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING +from typing import TYPE_CHECKING -from isaaclab.managers.action_manager import ActionTerm, ActionTermCfg +from isaaclab.managers.action_manager import ActionTermCfg from isaaclab.utils import configclass -from . import thrust_actions +if TYPE_CHECKING: + from .thrust_actions import ThrustAction @configclass @@ -70,7 +72,7 @@ class ThrustActionCfg(ActionTermCfg): - :class:`~isaaclab.managers.ActionTermCfg`: Base action term configuration """ - class_type: type[ActionTerm] = thrust_actions.ThrustAction + class_type: type["ThrustAction"] | str = "{DIR}.thrust_actions:ThrustAction" asset_name: str = MISSING """Name or regex expression of the asset that the action will be mapped to. diff --git a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor_cfg.py b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor_cfg.py index 5aaf9cd6731..92ef015a63d 100644 --- a/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor_cfg.py +++ b/source/isaaclab_contrib/isaaclab_contrib/sensors/tacsl_sensor/visuotactile_sensor_cfg.py @@ -8,6 +8,7 @@ from __future__ import annotations from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.markers import VisualizationMarkersCfg from isaaclab.markers.config import VISUO_TACTILE_SENSOR_MARKER_CFG @@ -15,7 +16,8 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR -from .visuotactile_sensor import VisuoTactileSensor +if TYPE_CHECKING: + from .visuotactile_sensor import VisuoTactileSensor ## # GelSight Render Configuration @@ -109,7 +111,7 @@ class VisuoTactileSensorCfg(SensorBaseCfg): It can capture tactile RGB/depth images and compute penalty-based contact forces. """ - class_type: type = VisuoTactileSensor + class_type: type[VisuoTactileSensor] | str = "{DIR}.visuotactile_sensor:VisuoTactileSensor" # Sensor type and capabilities render_cfg: GelSightRenderCfg = MISSING diff --git a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/locomanipulation_sdg_env_cfg.py b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/locomanipulation_sdg_env_cfg.py index f3c5dd6c47c..2ccefe4d0c7 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/locomanipulation_sdg_env_cfg.py +++ b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/locomanipulation_sdg_env_cfg.py @@ -8,17 +8,15 @@ from isaaclab.envs.mdp.recorders.recorders_cfg import ActionStateRecorderManagerCfg from isaaclab.managers import EventTermCfg as EventTerm from isaaclab.managers import TerminationTermCfg as DoneTerm -from isaaclab.managers.recorder_manager import RecorderTerm, RecorderTermCfg +from isaaclab.managers.recorder_manager import RecorderTermCfg from isaaclab.utils import configclass -from .locomanipulation_sdg_env import LocomanipulationSDGOutputDataRecorder - @configclass class LocomanipulationSDGOutputDataRecorderCfg(RecorderTermCfg): """Configuration for the step policy observation recorder term.""" - class_type: type[RecorderTerm] = LocomanipulationSDGOutputDataRecorder + class_type: type | str = "{DIR}.locomanipulation_sdg_env:LocomanipulationSDGOutputDataRecorder" @configclass diff --git a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object_cfg.py b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object_cfg.py index 280577baefb..7dbf060c27b 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/deformable_object/deformable_object_cfg.py @@ -5,19 +5,22 @@ from __future__ import annotations +from typing import TYPE_CHECKING + from isaaclab.assets.asset_base_cfg import AssetBaseCfg from isaaclab.markers import VisualizationMarkersCfg from isaaclab.markers.config import DEFORMABLE_TARGET_MARKER_CFG from isaaclab.utils import configclass -from .deformable_object import DeformableObject +if TYPE_CHECKING: + from .deformable_object import DeformableObject @configclass class DeformableObjectCfg(AssetBaseCfg): """Configuration parameters for a deformable object.""" - class_type: type = DeformableObject + class_type: type[DeformableObject] | str = "{DIR}.deformable_object:DeformableObject" visualizer_cfg: VisualizationMarkersCfg = DEFORMABLE_TARGET_MARKER_CFG.replace( prim_path="/Visuals/DeformableTarget" diff --git a/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper_cfg.py b/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper_cfg.py index a6e3bdb2ebb..7b2c3c5493f 100644 --- a/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/assets/surface_gripper/surface_gripper_cfg.py @@ -4,11 +4,13 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING +from typing import TYPE_CHECKING from isaaclab.assets.asset_base_cfg import AssetBaseCfg from isaaclab.utils import configclass -from .surface_gripper import SurfaceGripper +if TYPE_CHECKING: + from .surface_gripper import SurfaceGripper @configclass @@ -30,4 +32,4 @@ class SurfaceGripperCfg(AssetBaseCfg): retry_interval: float | None = None """The amount of time the gripper will spend trying to grasp an object.""" - class_type: type = SurfaceGripper + class_type: type["SurfaceGripper"] | str = "{DIR}.surface_gripper:SurfaceGripper" diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py index d30252c7877..a7e15fbab73 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py @@ -12,10 +12,8 @@ from isaaclab.physics import PhysicsCfg from isaaclab.utils import configclass -from .physx_manager import PhysxManager - if TYPE_CHECKING: - from isaaclab.physics import PhysicsManager + from .physx_manager import PhysxManager @configclass @@ -41,7 +39,7 @@ class PhysxCfg(PhysicsCfg): # PhysX Scene Settings # ------------------------------------------------------------------ - class_type: type[PhysicsManager] = PhysxManager + class_type: type[PhysxManager] | str = "{DIR}.physx_manager:PhysxManager" """The class type of the PhysxManager.""" # ------------------------------------------------------------------ diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env_cfg.py index f8e32f9fcc9..bada387b80d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env_cfg.py @@ -8,7 +8,6 @@ import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg -from isaaclab.envs.ui import BaseEnvWindow from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.terrains import TerrainImporterCfg @@ -27,7 +26,7 @@ class QuadcopterEnvCfg(DirectRLEnvCfg): state_space = 0 debug_vis = True - ui_window_class_type: BaseEnvWindow + ui_window_class_type: type | str | None = "{DIR}.quadcopter_env:QuadcopterEnvWindow" # simulation sim: SimulationCfg = SimulationCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/commands_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/commands_cfg.py index f12cf1be082..cbcb4577308 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/commands_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/commands_cfg.py @@ -3,14 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause +from typing import TYPE_CHECKING + from isaaclab.envs.mdp.commands.commands_cfg import UniformPoseCommandCfg from isaaclab.utils import configclass -from .drone_pose_command import DroneUniformPoseCommand +if TYPE_CHECKING: + from .drone_pose_command import DroneUniformPoseCommand @configclass class DroneUniformPoseCommandCfg(UniformPoseCommandCfg): """Configuration for uniform drone pose command generator.""" - class_type: type = DroneUniformPoseCommand + class_type: type["DroneUniformPoseCommand"] | str = "{DIR}.drone_pose_command:DroneUniformPoseCommand" diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/configs/action_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/configs/action_cfg.py index b195334ba68..320d7d738ea 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/configs/action_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/configs/action_cfg.py @@ -4,18 +4,22 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING +from typing import TYPE_CHECKING -from isaaclab.managers.action_manager import ActionTerm, ActionTermCfg +from isaaclab.managers.action_manager import ActionTermCfg from isaaclab.utils import configclass -from ..mdp.actions import AgileBasedLowerBodyAction +if TYPE_CHECKING: + from ..mdp.actions import AgileBasedLowerBodyAction @configclass class AgileBasedLowerBodyActionCfg(ActionTermCfg): """Configuration for the lower body action term that is based on Agile lower body RL policy.""" - class_type: type[ActionTerm] = AgileBasedLowerBodyAction + class_type: type["AgileBasedLowerBodyAction"] | str = ( + "isaaclab_tasks.manager_based.locomanipulation.pick_place.mdp.actions:AgileBasedLowerBodyAction" + ) """The class type for the lower body action term.""" joint_names: list[str] = MISSING diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/commands/pose_commands_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/commands/pose_commands_cfg.py index e3c83882a3f..97806a835e9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/commands/pose_commands_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/dexsuite/mdp/commands/pose_commands_cfg.py @@ -4,6 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING +from typing import TYPE_CHECKING import isaaclab.sim as sim_utils from isaaclab.managers import CommandTermCfg @@ -11,7 +12,8 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR -from . import pose_commands as dex_cmd +if TYPE_CHECKING: + from .pose_commands import ObjectUniformPoseCommand ALIGN_MARKER_CFG = VisualizationMarkersCfg( markers={ @@ -35,7 +37,7 @@ class ObjectUniformPoseCommandCfg(CommandTermCfg): """Configuration for uniform pose command generator.""" - class_type: type = dex_cmd.ObjectUniformPoseCommand + class_type: type["ObjectUniformPoseCommand"] | str = "{DIR}.pose_commands:ObjectUniformPoseCommand" asset_name: str = MISSING """Name of the coordinate referencing asset in the environment for which the commands are generated respect to.""" diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/mdp/commands/commands_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/mdp/commands/commands_cfg.py index 8c020137c0c..6fe3ad8235b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/mdp/commands/commands_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/mdp/commands/commands_cfg.py @@ -11,8 +11,6 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR -from .orientation_command import InHandReOrientationCommand - @configclass class InHandReOrientationCommandCfg(CommandTermCfg): @@ -21,7 +19,8 @@ class InHandReOrientationCommandCfg(CommandTermCfg): Please refer to the :class:`InHandReOrientationCommand` class for more details. """ - class_type: type = InHandReOrientationCommand + class_type: type | str = "{DIR}.orientation_command:InHandReOrientationCommand" + resampling_time_range: tuple[float, float] = (1e6, 1e6) # no resampling based on time asset_name: str = MISSING diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action.py index 50a419ad7ef..43de222a506 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action.py @@ -16,6 +16,8 @@ from isaaclab.markers.config import BLUE_ARROW_X_MARKER_CFG, GREEN_ARROW_X_MARKER_CFG from isaaclab.utils.assets import check_file_path, read_file +from .pre_trained_policy_action_cfg import PreTrainedPolicyActionCfg # noqa: F401 + if TYPE_CHECKING: from isaaclab.assets import Articulation from isaaclab.envs import ManagerBasedRLEnv diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action_cfg.py index a69d3791a51..0c7b54152df 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/mdp/pre_trained_policy_action_cfg.py @@ -8,8 +8,6 @@ from isaaclab.managers import ActionTermCfg, ObservationGroupCfg from isaaclab.utils import configclass -from .pre_trained_policy_action import PreTrainedPolicyAction - @configclass class PreTrainedPolicyActionCfg(ActionTermCfg): @@ -18,7 +16,7 @@ class PreTrainedPolicyActionCfg(ActionTermCfg): See :class:`PreTrainedPolicyAction` for more details. """ - class_type: type | str = PreTrainedPolicyAction + class_type: type | str = "{DIR}.pre_trained_policy_action:PreTrainedPolicyAction" """Class of the action term.""" asset_name: str = MISSING