From 4ca3294ab4473148a383bc80c22aa83d188266f0 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Sun, 6 Oct 2024 20:47:28 +0200 Subject: [PATCH 01/11] fix run instructions --- source/standalone/tutorials/03_envs/create_cube_base_env.py | 2 +- .../standalone/tutorials/03_envs/create_quadruped_base_env.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/source/standalone/tutorials/03_envs/create_cube_base_env.py b/source/standalone/tutorials/03_envs/create_cube_base_env.py index 92a47ed6cf..54dcc14445 100644 --- a/source/standalone/tutorials/03_envs/create_cube_base_env.py +++ b/source/standalone/tutorials/03_envs/create_cube_base_env.py @@ -14,7 +14,7 @@ .. code-block:: bash # Run the script - ./isaaclab.sh -p source/standalone/tutorials/04_envs/floating_cube.py --num_envs 32 + ./isaaclab.sh -p source/standalone/tutorials/03_envs/create_cube_base_env.py --num_envs 32 """ from __future__ import annotations diff --git a/source/standalone/tutorials/03_envs/create_quadruped_base_env.py b/source/standalone/tutorials/03_envs/create_quadruped_base_env.py index 56a13b52ba..59202df901 100644 --- a/source/standalone/tutorials/03_envs/create_quadruped_base_env.py +++ b/source/standalone/tutorials/03_envs/create_quadruped_base_env.py @@ -13,7 +13,7 @@ .. code-block:: bash # Run the script - ./isaaclab.sh -p source/standalone/tutorials/04_envs/quadruped_base_env.py --num_envs 32 + ./isaaclab.sh -p source/standalone/tutorials/03_envs/create_quadruped_base_env.py --num_envs 32 """ From dc7dd3195645586ff9b8ae660b8ccf2612f65ca0 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Sun, 6 Oct 2024 21:12:32 +0200 Subject: [PATCH 02/11] adds event for randomization --- .../omni/isaac/lab/envs/mdp/events.py | 104 ++++++++++++++++++ 1 file changed, 104 insertions(+) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py index 8f2d737eb7..0f74f59803 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py @@ -19,7 +19,9 @@ from typing import TYPE_CHECKING, Literal import carb +import omni.usd import omni.physics.tensors.impl.api as physx +from pxr import Gf, Sdf import omni.isaac.lab.sim as sim_utils import omni.isaac.lab.utils.math as math_utils @@ -32,6 +34,108 @@ from omni.isaac.lab.envs import ManagerBasedEnv +def randomize_shape_color( + env: ManagerBasedEnv, + env_ids: torch.Tensor | None, + asset_cfg: SceneEntityCfg, +): + """Randomize the color of a shape. + + This function randomizes the color of USD shapes created using :class:`omni.isaac.lab.sim.spawn.ShapeCfg` + class. It modifies the attribute: "geometry/material/Shader.inputs:diffuseColor" under the prims + corresponding to the asset. + """ + # extract the used quantities (to enable type-hinting) + asset: RigidObject = env.scene[asset_cfg.name] + + # resolve environment ids + if env_ids is None: + env_ids = torch.arange(env.scene.num_envs, device="cpu") + else: + env_ids = env_ids.cpu() + + # acquire stage + stage = omni.usd.get_context().get_stage() + # resolve prim paths for spawning and cloning + prim_paths = sim_utils.find_matching_prim_paths(asset.cfg.prim_path) + + # sample values + rand_samples = math_utils.sample_uniform(0.0, 1.0, (len(env_ids), 3), device="cpu").tolist() + + # use sdf changeblock for faster processing of USD properties + with Sdf.ChangeBlock(): + for i, env_id in enumerate(env_ids): + # spawn single instance + prim_spec = Sdf.CreatePrimInLayer(stage.GetRootLayer(), prim_paths[env_id]) + + # get the attribute to randomize + color_spec = prim_spec.GetAttributeAtPath( + prim_paths[env_id] + "/geometry/material/Shader.inputs:diffuseColor" + ) + color_spec.default = Gf.Vec3f(*rand_samples[i]) + + +def randomize_scale( + env: ManagerBasedEnv, + env_ids: torch.Tensor | None, + scale_range: tuple[float, float] | dict[str, tuple[float, float]], + asset_cfg: SceneEntityCfg, +): + """Randomize the scale of an asset along all dimensions. + + This function modifies the "xformOp:scale" property of all the prims corresponding to the asset. + + It takes a tuple or dictionary for the scale ranges. If it is a tuple, then the scaling along + individual axis is performed equally. If it is a dictionary, the scaling is independent across each dimension. + + The keys of the dictionary are ``x``, ``y``, and ``z``. The values are tuples of the form ``(min, max)``. + If the dictionary does not contain a key, the range is set to one for that axis. + + .. attention:: + Since this function modifies USD properties, it should only be used before the simulation starts + playing. This corresponds to the event mode named "spawn". Using it at simulation time, may lead to + unpredictable behaviors. + + .. note:: + When randomizing the scale of individual assets, please make sure to set + :attr:`omni.isaac.lab.scene.InteractiveSceneCfg.replicate_physics` to False. This ensures that physics + parser will parse the individual asset properties separately. + + """ + # extract the used quantities (to enable type-hinting) + asset: RigidObject | Articulation = env.scene[asset_cfg.name] + + # resolve environment ids + if env_ids is None: + env_ids = torch.arange(env.scene.num_envs, device="cpu") + else: + env_ids = env_ids.cpu() + + # acquire stage + stage = omni.usd.get_context().get_stage() + # resolve prim paths for spawning and cloning + prim_paths = sim_utils.find_matching_prim_paths(asset.cfg.prim_path) + + # sample scale values + if isinstance(scale_range, dict): + range_list = [scale_range.get(key, (1.0, 1.0)) for key in ["x", "y", "z"]] + ranges = torch.tensor(range_list, device="cpu") + rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 3), device="cpu").tolist() + else: + rand_samples = math_utils.sample_uniform(*scale_range, (len(env_ids), 1), device="cpu") + rand_samples = rand_samples.repeat(1, 3).tolist() + + # use sdf changeblock for faster processing of USD properties + with Sdf.ChangeBlock(): + for i, env_id in enumerate(env_ids): + # spawn single instance + prim_spec = Sdf.CreatePrimInLayer(stage.GetRootLayer(), prim_paths[env_id]) + + # get the attribute to randomize + scale_spec = prim_spec.GetAttributeAtPath(prim_paths[env_id] + ".xformOp:scale") + scale_spec.default = Gf.Vec3f(*rand_samples[i]) + + def randomize_rigid_body_material( env: ManagerBasedEnv, env_ids: torch.Tensor | None, From e0caec0032661060bb6a2b42f4c7ea0fd942ce46 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Sun, 6 Oct 2024 21:12:50 +0200 Subject: [PATCH 03/11] adds scene level randomizations --- .../omni/isaac/lab/envs/manager_based_env.py | 17 +++++++++++++++++ .../omni/isaac/lab/managers/event_manager.py | 3 ++- .../tutorials/03_envs/create_cube_base_env.py | 17 ++++++++++++++++- 3 files changed, 35 insertions(+), 2 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py index 4cc1b86b8c..f193faad05 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py @@ -116,6 +116,23 @@ def __init__(self, cfg: ManagerBasedEnvCfg): self.scene = InteractiveScene(self.cfg.scene) print("[INFO]: Scene manager: ", self.scene) + # check for valid config type + from omni.isaac.lab.managers import EventTermCfg + # randomization at scene level + for term_name, term_cfg in self.cfg.events.__dict__.items(): + # check for non config + if term_cfg is None: + continue + if not isinstance(term_cfg, EventTermCfg): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type EventTermCfg." + f" Received: '{type(term_cfg)}'." + ) + if term_cfg.mode == "scene": + if self.scene.cfg.replicate_physics: + carb.log_warn("You are not smart.") + term_cfg.func(self, None, **term_cfg.params) + # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py index e8aa7407ed..1ce385c6ba 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py @@ -38,7 +38,8 @@ class EventManager(ManagerBase): For a typical training process, you may want to apply events in the following modes: - - "startup": Event is applied once at the beginning of the training. + - "scene": Event is applied once after designing the scene. + - "startup": Event is applied once after the simulation starts playing. - "reset": Event is applied at every reset. - "interval": Event is applied at pre-specified intervals of time. diff --git a/source/standalone/tutorials/03_envs/create_cube_base_env.py b/source/standalone/tutorials/03_envs/create_cube_base_env.py index 54dcc14445..9ace087177 100644 --- a/source/standalone/tutorials/03_envs/create_cube_base_env.py +++ b/source/standalone/tutorials/03_envs/create_cube_base_env.py @@ -236,6 +236,21 @@ class EventCfg: }, ) + randomize_color = EventTerm( + func=mdp.randomize_shape_color, + mode="scene", + params={"asset_cfg": SceneEntityCfg("cube")}, + ) + + randomize_scale = EventTerm( + func=mdp.randomize_scale, + mode="scene", + params={ + "scale_range": {"x": (0.5, 1.5), "y": (0.5, 1.5), "z": (0.5, 1.5)}, + "asset_cfg": SceneEntityCfg("cube"), + }, + ) + ## # Environment configuration @@ -247,7 +262,7 @@ class CubeEnvCfg(ManagerBasedEnvCfg): """Configuration for the locomotion velocity-tracking environment.""" # Scene settings - scene: MySceneCfg = MySceneCfg(num_envs=args_cli.num_envs, env_spacing=2.5) + scene: MySceneCfg = MySceneCfg(num_envs=args_cli.num_envs, env_spacing=2.5, replicate_physics=False) # Basic settings observations: ObservationsCfg = ObservationsCfg() actions: ActionsCfg = ActionsCfg() From 89df3ecb3f719f945cc02760c991011b78a4ef09 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Sun, 6 Oct 2024 21:13:10 +0200 Subject: [PATCH 04/11] runs formatter --- .../omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py | 3 ++- .../omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py | 6 +++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py index f193faad05..b2b83677c5 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py @@ -118,6 +118,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): # check for valid config type from omni.isaac.lab.managers import EventTermCfg + # randomization at scene level for term_name, term_cfg in self.cfg.events.__dict__.items(): # check for non config @@ -132,7 +133,7 @@ def __init__(self, cfg: ManagerBasedEnvCfg): if self.scene.cfg.replicate_physics: carb.log_warn("You are not smart.") term_cfg.func(self, None, **term_cfg.params) - + # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py index 0f74f59803..1246609104 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py @@ -19,8 +19,8 @@ from typing import TYPE_CHECKING, Literal import carb -import omni.usd import omni.physics.tensors.impl.api as physx +import omni.usd from pxr import Gf, Sdf import omni.isaac.lab.sim as sim_utils @@ -40,8 +40,8 @@ def randomize_shape_color( asset_cfg: SceneEntityCfg, ): """Randomize the color of a shape. - - This function randomizes the color of USD shapes created using :class:`omni.isaac.lab.sim.spawn.ShapeCfg` + + This function randomizes the color of USD shapes created using :class:`omni.isaac.lab.sim.spawn.ShapeCfg` class. It modifies the attribute: "geometry/material/Shader.inputs:diffuseColor" under the prims corresponding to the asset. """ From 8f24afa3c403e7eb7715aca9b925373fd01edb0d Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Sun, 6 Oct 2024 21:40:36 +0200 Subject: [PATCH 05/11] adds better docs --- .../omni/isaac/lab/envs/manager_based_env.py | 38 ++++++++++--------- 1 file changed, 21 insertions(+), 17 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py index b2b83677c5..582d00d736 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py @@ -11,7 +11,7 @@ import carb import omni.isaac.core.utils.torch as torch_utils -from omni.isaac.lab.managers import ActionManager, EventManager, ObservationManager +from omni.isaac.lab.managers import ActionManager, EventManager, EventTermCfg, ObservationManager from omni.isaac.lab.scene import InteractiveScene from omni.isaac.lab.sim import SimulationContext from omni.isaac.lab.utils.timer import Timer @@ -116,23 +116,27 @@ def __init__(self, cfg: ManagerBasedEnvCfg): self.scene = InteractiveScene(self.cfg.scene) print("[INFO]: Scene manager: ", self.scene) - # check for valid config type - from omni.isaac.lab.managers import EventTermCfg - # randomization at scene level - for term_name, term_cfg in self.cfg.events.__dict__.items(): - # check for non config - if term_cfg is None: - continue - if not isinstance(term_cfg, EventTermCfg): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type EventTermCfg." - f" Received: '{type(term_cfg)}'." - ) - if term_cfg.mode == "scene": - if self.scene.cfg.replicate_physics: - carb.log_warn("You are not smart.") - term_cfg.func(self, None, **term_cfg.params) + with Timer("[INFO]: Time taken for scene-level randomization", "scene_randomization"): + for term_name, term_cfg in self.cfg.events.__dict__.items(): + # check for non config + if term_cfg is None: + continue + # check for valid config type + if not isinstance(term_cfg, EventTermCfg): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type EventTermCfg." + f" Received: '{type(term_cfg)}'." + ) + # call event terms corresponding to the scene-level randomization + if term_cfg.mode == "scene": + if self.scene.cfg.replicate_physics: + carb.log_warn( + "Replicate physics is enabled in the 'InteractiveScene' configuration." + " This may adversely affect PhysX parsing of scene information." + " We recommend disabling this property." + ) + term_cfg.func(self, None, **term_cfg.params) # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning From d3b060557b7ae9c61cd5983dc51997efd522128a Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Sun, 6 Oct 2024 21:43:51 +0200 Subject: [PATCH 06/11] adds support for classes --- .../omni/isaac/lab/envs/manager_based_env.py | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py index 582d00d736..ed599ff208 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py @@ -4,6 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause import builtins +import inspect import torch from collections.abc import Sequence from typing import Any @@ -11,7 +12,7 @@ import carb import omni.isaac.core.utils.torch as torch_utils -from omni.isaac.lab.managers import ActionManager, EventManager, EventTermCfg, ObservationManager +from omni.isaac.lab.managers import ActionManager, EventManager, EventTermCfg, ManagerTermBase, ObservationManager from omni.isaac.lab.scene import InteractiveScene from omni.isaac.lab.sim import SimulationContext from omni.isaac.lab.utils.timer import Timer @@ -117,6 +118,8 @@ def __init__(self, cfg: ManagerBasedEnvCfg): print("[INFO]: Scene manager: ", self.scene) # randomization at scene level + # we mimic operations from event manager since we cannot initialize event manager here. + # sometimes it requires joints and body names which are only available once simulation starts playing. with Timer("[INFO]: Time taken for scene-level randomization", "scene_randomization"): for term_name, term_cfg in self.cfg.events.__dict__.items(): # check for non config @@ -136,6 +139,15 @@ def __init__(self, cfg: ManagerBasedEnvCfg): " This may adversely affect PhysX parsing of scene information." " We recommend disabling this property." ) + # initialize the term if it is a class + if inspect.isclass(term_cfg.func): + if not issubclass(term_cfg.func, ManagerTermBase): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type ManagerTermBase." + f" Received: '{type(term_cfg.func)}'." + ) + term_cfg.func = term_cfg.func(cfg=term_cfg, env=self._env) + # call the term term_cfg.func(self, None, **term_cfg.params) # set up camera viewport controller From b19b3b17f8726e1678c3d3416b394e70b4fcb351 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Mon, 7 Oct 2024 12:02:25 +0200 Subject: [PATCH 07/11] removes unnecessary block --- .../omni.isaac.lab/omni/isaac/lab/managers/event_manager.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py index 1ce385c6ba..c5ad7c8c0a 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/event_manager.py @@ -53,9 +53,6 @@ class EventManager(ManagerBase): """ - _env: ManagerBasedEnv - """The environment instance.""" - def __init__(self, cfg: object, env: ManagerBasedEnv): """Initialize the event manager. From ca136a80009a0f517899710fe86cb459575a1f10 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Mon, 7 Oct 2024 13:46:47 +0200 Subject: [PATCH 08/11] makes function for scene term parsing --- .../omni/isaac/lab/envs/direct_marl_env.py | 56 ++++++++++++- .../omni/isaac/lab/envs/direct_rl_env.py | 56 ++++++++++++- .../omni/isaac/lab/envs/manager_based_env.py | 79 +++++++++++-------- 3 files changed, 158 insertions(+), 33 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py index ab7cb5e3c0..e8732a3656 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py @@ -21,7 +21,7 @@ import omni.kit.app from omni.isaac.version import get_version -from omni.isaac.lab.managers import EventManager +from omni.isaac.lab.managers import EventManager, EventTermCfg, ManagerTermBase from omni.isaac.lab.scene import InteractiveScene from omni.isaac.lab.sim import SimulationContext from omni.isaac.lab.utils.noise import NoiseModel @@ -113,6 +113,10 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar self._setup_scene() print("[INFO]: Scene manager: ", self.scene) + # randomization at scene level + with Timer("[INFO]: Time taken for scene randomization", "scene_randomization"): + self._apply_scene_randomization() + # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for @@ -613,6 +617,56 @@ def _reset_idx(self, env_ids: Sequence[int]): # reset the episode length buffer self.episode_length_buf[env_ids] = 0 + def _apply_scene_randomization(self): + """Apply scene-level randomization. + + This function applies the scene-level randomization based on the configuration provided + to the event manager. Since the event manager is not initialized at this point, we mimic + the operations of the event manager to apply the scene-level randomization. + + It must be called only before the simulation/physics is started. + """ + # check if events exist + if not self.cfg.events: + return + + # check if scene randomization is enabled + applied_scene_randomization = False + + # iterate over all event terms + for term_name, term_cfg in self.cfg.events.__dict__.items(): + # check for non config + if term_cfg is None: + continue + # check for valid config type + if not isinstance(term_cfg, EventTermCfg): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type EventTermCfg." + f" Received: '{type(term_cfg)}'." + ) + # call event terms corresponding to the scene-level randomization + if term_cfg.mode == "scene": + # enable scene randomization + applied_scene_randomization = True + # initialize the term if it is a class + if inspect.isclass(term_cfg.func): + if not issubclass(term_cfg.func, ManagerTermBase): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type ManagerTermBase." + f" Received: '{type(term_cfg.func)}'." + ) + term_cfg.func = term_cfg.func(cfg=term_cfg, env=self) + # call the term + term_cfg.func(self, None, **term_cfg.params) + + # warn the user that replicate physics may affect PhysX parsing + if self.scene.cfg.replicate_physics and applied_scene_randomization: + carb.log_warn( + "Replicate physics is enabled in the 'InteractiveScene' configuration." + " This may adversely affect PhysX parsing of scene information." + " We recommend disabling this property." + ) + """ Implementation-specific functions. """ diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py index 656bf3e2dc..35153a99d8 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py @@ -21,7 +21,7 @@ import omni.kit.app from omni.isaac.version import get_version -from omni.isaac.lab.managers import EventManager +from omni.isaac.lab.managers import EventManager, EventTermCfg, ManagerTermBase from omni.isaac.lab.scene import InteractiveScene from omni.isaac.lab.sim import SimulationContext from omni.isaac.lab.utils.noise import NoiseModel @@ -118,6 +118,10 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs self._setup_scene() print("[INFO]: Scene manager: ", self.scene) + # randomization at scene level + with Timer("[INFO]: Time taken for scene randomization", "scene_randomization"): + self._apply_scene_randomization() + # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning # FIXME: This needs to be fixed in the future when we unify the UI functionalities even for @@ -551,6 +555,56 @@ def _reset_idx(self, env_ids: Sequence[int]): # reset the episode length buffer self.episode_length_buf[env_ids] = 0 + def _apply_scene_randomization(self): + """Apply scene-level randomization. + + This function applies the scene-level randomization based on the configuration provided + to the event manager. Since the event manager is not initialized at this point, we mimic + the operations of the event manager to apply the scene-level randomization. + + It must be called only before the simulation/physics is started. + """ + # check if events exist + if not self.cfg.events: + return + + # check if scene randomization is enabled + applied_scene_randomization = False + + # iterate over all event terms + for term_name, term_cfg in self.cfg.events.__dict__.items(): + # check for non config + if term_cfg is None: + continue + # check for valid config type + if not isinstance(term_cfg, EventTermCfg): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type EventTermCfg." + f" Received: '{type(term_cfg)}'." + ) + # call event terms corresponding to the scene-level randomization + if term_cfg.mode == "scene": + # enable scene randomization + applied_scene_randomization = True + # initialize the term if it is a class + if inspect.isclass(term_cfg.func): + if not issubclass(term_cfg.func, ManagerTermBase): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type ManagerTermBase." + f" Received: '{type(term_cfg.func)}'." + ) + term_cfg.func = term_cfg.func(cfg=term_cfg, env=self) + # call the term + term_cfg.func(self, None, **term_cfg.params) + + # warn the user that replicate physics may affect PhysX parsing + if self.scene.cfg.replicate_physics and applied_scene_randomization: + carb.log_warn( + "Replicate physics is enabled in the 'InteractiveScene' configuration." + " This may adversely affect PhysX parsing of scene information." + " We recommend disabling this property." + ) + """ Implementation-specific functions. """ diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py index ed599ff208..cc904bff6b 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py @@ -118,37 +118,8 @@ def __init__(self, cfg: ManagerBasedEnvCfg): print("[INFO]: Scene manager: ", self.scene) # randomization at scene level - # we mimic operations from event manager since we cannot initialize event manager here. - # sometimes it requires joints and body names which are only available once simulation starts playing. - with Timer("[INFO]: Time taken for scene-level randomization", "scene_randomization"): - for term_name, term_cfg in self.cfg.events.__dict__.items(): - # check for non config - if term_cfg is None: - continue - # check for valid config type - if not isinstance(term_cfg, EventTermCfg): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type EventTermCfg." - f" Received: '{type(term_cfg)}'." - ) - # call event terms corresponding to the scene-level randomization - if term_cfg.mode == "scene": - if self.scene.cfg.replicate_physics: - carb.log_warn( - "Replicate physics is enabled in the 'InteractiveScene' configuration." - " This may adversely affect PhysX parsing of scene information." - " We recommend disabling this property." - ) - # initialize the term if it is a class - if inspect.isclass(term_cfg.func): - if not issubclass(term_cfg.func, ManagerTermBase): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type ManagerTermBase." - f" Received: '{type(term_cfg.func)}'." - ) - term_cfg.func = term_cfg.func(cfg=term_cfg, env=self._env) - # call the term - term_cfg.func(self, None, **term_cfg.params) + with Timer("[INFO]: Time taken for scene randomization", "scene_randomization"): + self._apply_scene_randomization() # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning @@ -407,3 +378,49 @@ def _reset_idx(self, env_ids: Sequence[int]): # -- event manager info = self.event_manager.reset(env_ids) self.extras["log"].update(info) + + def _apply_scene_randomization(self): + """Apply scene-level randomization. + + This function applies the scene-level randomization based on the configuration provided + to the event manager. Since the event manager is not initialized at this point, we mimic + the operations of the event manager to apply the scene-level randomization. + + It must be called only before the simulation/physics is started. + """ + # check if scene randomization is enabled + applied_scene_randomization = False + + # iterate over all event terms + for term_name, term_cfg in self.cfg.events.__dict__.items(): + # check for non config + if term_cfg is None: + continue + # check for valid config type + if not isinstance(term_cfg, EventTermCfg): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type EventTermCfg." + f" Received: '{type(term_cfg)}'." + ) + # call event terms corresponding to the scene-level randomization + if term_cfg.mode == "scene": + # enable scene randomization + applied_scene_randomization = True + # initialize the term if it is a class + if inspect.isclass(term_cfg.func): + if not issubclass(term_cfg.func, ManagerTermBase): + raise TypeError( + f"Configuration for the term '{term_name}' is not of type ManagerTermBase." + f" Received: '{type(term_cfg.func)}'." + ) + term_cfg.func = term_cfg.func(cfg=term_cfg, env=self) + # call the term + term_cfg.func(self, None, **term_cfg.params) + + # warn the user that replicate physics may affect PhysX parsing + if self.scene.cfg.replicate_physics and applied_scene_randomization: + carb.log_warn( + "Replicate physics is enabled in the 'InteractiveScene' configuration." + " This may adversely affect PhysX parsing of scene information." + " We recommend disabling this property." + ) From 98fd02082d461e463996b809ffc1d9b13b7d6663 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Mon, 7 Oct 2024 14:09:22 +0200 Subject: [PATCH 09/11] makes a static method to simplify config parsing --- .../omni/isaac/lab/envs/direct_marl_env.py | 89 ++++++++----------- .../omni/isaac/lab/envs/direct_rl_env.py | 89 ++++++++----------- .../omni/isaac/lab/envs/manager_based_env.py | 76 +++++++--------- .../omni/isaac/lab/managers/manager_base.py | 60 ++++++++----- 4 files changed, 145 insertions(+), 169 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py index e8732a3656..2d3ad68c6c 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py @@ -21,7 +21,7 @@ import omni.kit.app from omni.isaac.version import get_version -from omni.isaac.lab.managers import EventManager, EventTermCfg, ManagerTermBase +from omni.isaac.lab.managers import EventManager, ManagerBase from omni.isaac.lab.scene import InteractiveScene from omni.isaac.lab.sim import SimulationContext from omni.isaac.lab.utils.noise import NoiseModel @@ -567,6 +567,43 @@ def set_debug_vis(self, debug_vis: bool) -> bool: Helper functions. """ + def _apply_scene_randomization(self): + """Apply scene-level randomization. + + This function applies the scene-level randomization based on the configuration provided + to the event manager. Since the event manager is not initialized at this point, we mimic + the operations of the event manager to apply the scene-level randomization. + + It must be called only before the simulation/physics is started. + """ + # check if events exist + if not self.cfg.events: + return + + # check if scene randomization is enabled + applied_scene_randomization = False + # iterate over all event terms + for term_name, term_cfg in self.cfg.events.__dict__.items(): + # check for non config + if term_cfg is None: + continue + # call event terms corresponding to the scene-level randomization + if term_cfg.mode == "scene": + # resolve term config + ManagerBase.resolve_term_cfg(self, term_name, term_cfg, min_argc=2) + # enable scene randomization + applied_scene_randomization = True + # call the term + term_cfg.func(self, None, **term_cfg.params) + + # warn the user that replicate physics may affect PhysX parsing + if self.scene.cfg.replicate_physics and applied_scene_randomization: + carb.log_warn( + "Replicate physics is enabled in the 'InteractiveScene' configuration." + " This may adversely affect PhysX parsing of scene information." + " We recommend disabling this property." + ) + def _configure_env_spaces(self): """Configure the spaces for the environment.""" self.agents = self.cfg.possible_agents @@ -617,56 +654,6 @@ def _reset_idx(self, env_ids: Sequence[int]): # reset the episode length buffer self.episode_length_buf[env_ids] = 0 - def _apply_scene_randomization(self): - """Apply scene-level randomization. - - This function applies the scene-level randomization based on the configuration provided - to the event manager. Since the event manager is not initialized at this point, we mimic - the operations of the event manager to apply the scene-level randomization. - - It must be called only before the simulation/physics is started. - """ - # check if events exist - if not self.cfg.events: - return - - # check if scene randomization is enabled - applied_scene_randomization = False - - # iterate over all event terms - for term_name, term_cfg in self.cfg.events.__dict__.items(): - # check for non config - if term_cfg is None: - continue - # check for valid config type - if not isinstance(term_cfg, EventTermCfg): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type EventTermCfg." - f" Received: '{type(term_cfg)}'." - ) - # call event terms corresponding to the scene-level randomization - if term_cfg.mode == "scene": - # enable scene randomization - applied_scene_randomization = True - # initialize the term if it is a class - if inspect.isclass(term_cfg.func): - if not issubclass(term_cfg.func, ManagerTermBase): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type ManagerTermBase." - f" Received: '{type(term_cfg.func)}'." - ) - term_cfg.func = term_cfg.func(cfg=term_cfg, env=self) - # call the term - term_cfg.func(self, None, **term_cfg.params) - - # warn the user that replicate physics may affect PhysX parsing - if self.scene.cfg.replicate_physics and applied_scene_randomization: - carb.log_warn( - "Replicate physics is enabled in the 'InteractiveScene' configuration." - " This may adversely affect PhysX parsing of scene information." - " We recommend disabling this property." - ) - """ Implementation-specific functions. """ diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py index 35153a99d8..b0d622e8e4 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py @@ -21,7 +21,7 @@ import omni.kit.app from omni.isaac.version import get_version -from omni.isaac.lab.managers import EventManager, EventTermCfg, ManagerTermBase +from omni.isaac.lab.managers import EventManager, ManagerBase from omni.isaac.lab.scene import InteractiveScene from omni.isaac.lab.sim import SimulationContext from omni.isaac.lab.utils.noise import NoiseModel @@ -509,6 +509,43 @@ def set_debug_vis(self, debug_vis: bool) -> bool: Helper functions. """ + def _apply_scene_randomization(self): + """Apply scene-level randomization. + + This function applies the scene-level randomization based on the configuration provided + to the event manager. Since the event manager is not initialized at this point, we mimic + the operations of the event manager to apply the scene-level randomization. + + It must be called only before the simulation/physics is started. + """ + # check if events exist + if not self.cfg.events: + return + + # check if scene randomization is enabled + applied_scene_randomization = False + # iterate over all event terms + for term_name, term_cfg in self.cfg.events.__dict__.items(): + # check for non config + if term_cfg is None: + continue + # call event terms corresponding to the scene-level randomization + if term_cfg.mode == "scene": + # resolve term config + ManagerBase.resolve_term_cfg(self, term_name, term_cfg, min_argc=2) + # enable scene randomization + applied_scene_randomization = True + # call the term + term_cfg.func(self, None, **term_cfg.params) + + # warn the user that replicate physics may affect PhysX parsing + if self.scene.cfg.replicate_physics and applied_scene_randomization: + carb.log_warn( + "Replicate physics is enabled in the 'InteractiveScene' configuration." + " This may adversely affect PhysX parsing of scene information." + " We recommend disabling this property." + ) + def _configure_gym_env_spaces(self): """Configure the action and observation spaces for the Gym environment.""" # observation space (unbounded since we don't impose any limits) @@ -555,56 +592,6 @@ def _reset_idx(self, env_ids: Sequence[int]): # reset the episode length buffer self.episode_length_buf[env_ids] = 0 - def _apply_scene_randomization(self): - """Apply scene-level randomization. - - This function applies the scene-level randomization based on the configuration provided - to the event manager. Since the event manager is not initialized at this point, we mimic - the operations of the event manager to apply the scene-level randomization. - - It must be called only before the simulation/physics is started. - """ - # check if events exist - if not self.cfg.events: - return - - # check if scene randomization is enabled - applied_scene_randomization = False - - # iterate over all event terms - for term_name, term_cfg in self.cfg.events.__dict__.items(): - # check for non config - if term_cfg is None: - continue - # check for valid config type - if not isinstance(term_cfg, EventTermCfg): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type EventTermCfg." - f" Received: '{type(term_cfg)}'." - ) - # call event terms corresponding to the scene-level randomization - if term_cfg.mode == "scene": - # enable scene randomization - applied_scene_randomization = True - # initialize the term if it is a class - if inspect.isclass(term_cfg.func): - if not issubclass(term_cfg.func, ManagerTermBase): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type ManagerTermBase." - f" Received: '{type(term_cfg.func)}'." - ) - term_cfg.func = term_cfg.func(cfg=term_cfg, env=self) - # call the term - term_cfg.func(self, None, **term_cfg.params) - - # warn the user that replicate physics may affect PhysX parsing - if self.scene.cfg.replicate_physics and applied_scene_randomization: - carb.log_warn( - "Replicate physics is enabled in the 'InteractiveScene' configuration." - " This may adversely affect PhysX parsing of scene information." - " We recommend disabling this property." - ) - """ Implementation-specific functions. """ diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py index cc904bff6b..6a914f0ff7 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/manager_based_env.py @@ -4,7 +4,6 @@ # SPDX-License-Identifier: BSD-3-Clause import builtins -import inspect import torch from collections.abc import Sequence from typing import Any @@ -12,7 +11,7 @@ import carb import omni.isaac.core.utils.torch as torch_utils -from omni.isaac.lab.managers import ActionManager, EventManager, EventTermCfg, ManagerTermBase, ObservationManager +from omni.isaac.lab.managers import ActionManager, EventManager, ManagerBase, ObservationManager from omni.isaac.lab.scene import InteractiveScene from omni.isaac.lab.sim import SimulationContext from omni.isaac.lab.utils.timer import Timer @@ -351,34 +350,6 @@ def close(self): Helper functions. """ - def _reset_idx(self, env_ids: Sequence[int]): - """Reset environments based on specified indices. - - Args: - env_ids: List of environment ids which must be reset - """ - # reset the internal buffers of the scene elements - self.scene.reset(env_ids) - - # apply events such as randomization for environments that need a reset - if "reset" in self.event_manager.available_modes: - env_step_count = self._sim_step_counter // self.cfg.decimation - self.event_manager.apply(mode="reset", env_ids=env_ids, global_env_step_count=env_step_count) - - # iterate over all managers and reset them - # this returns a dictionary of information which is stored in the extras - # note: This is order-sensitive! Certain things need be reset before others. - self.extras["log"] = dict() - # -- observation manager - info = self.observation_manager.reset(env_ids) - self.extras["log"].update(info) - # -- action manager - info = self.action_manager.reset(env_ids) - self.extras["log"].update(info) - # -- event manager - info = self.event_manager.reset(env_ids) - self.extras["log"].update(info) - def _apply_scene_randomization(self): """Apply scene-level randomization. @@ -390,30 +361,17 @@ def _apply_scene_randomization(self): """ # check if scene randomization is enabled applied_scene_randomization = False - # iterate over all event terms for term_name, term_cfg in self.cfg.events.__dict__.items(): # check for non config if term_cfg is None: continue - # check for valid config type - if not isinstance(term_cfg, EventTermCfg): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type EventTermCfg." - f" Received: '{type(term_cfg)}'." - ) # call event terms corresponding to the scene-level randomization if term_cfg.mode == "scene": + # resolve term config + ManagerBase.resolve_term_cfg(self, term_name, term_cfg, min_argc=2) # enable scene randomization applied_scene_randomization = True - # initialize the term if it is a class - if inspect.isclass(term_cfg.func): - if not issubclass(term_cfg.func, ManagerTermBase): - raise TypeError( - f"Configuration for the term '{term_name}' is not of type ManagerTermBase." - f" Received: '{type(term_cfg.func)}'." - ) - term_cfg.func = term_cfg.func(cfg=term_cfg, env=self) # call the term term_cfg.func(self, None, **term_cfg.params) @@ -424,3 +382,31 @@ def _apply_scene_randomization(self): " This may adversely affect PhysX parsing of scene information." " We recommend disabling this property." ) + + def _reset_idx(self, env_ids: Sequence[int]): + """Reset environments based on specified indices. + + Args: + env_ids: List of environment ids which must be reset + """ + # reset the internal buffers of the scene elements + self.scene.reset(env_ids) + + # apply events such as randomization for environments that need a reset + if "reset" in self.event_manager.available_modes: + env_step_count = self._sim_step_counter // self.cfg.decimation + self.event_manager.apply(mode="reset", env_ids=env_ids, global_env_step_count=env_step_count) + + # iterate over all managers and reset them + # this returns a dictionary of information which is stored in the extras + # note: This is order-sensitive! Certain things need be reset before others. + self.extras["log"] = dict() + # -- observation manager + info = self.observation_manager.reset(env_ids) + self.extras["log"].update(info) + # -- action manager + info = self.action_manager.reset(env_ids) + self.extras["log"].update(info) + # -- event manager + info = self.event_manager.reset(env_ids) + self.extras["log"].update(info) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/manager_base.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/manager_base.py index a11d0f6fdf..ad413946d6 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/manager_base.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/managers/manager_base.py @@ -192,23 +192,14 @@ def find_terms(self, name_keys: str | Sequence[str]) -> list[str]: # return the matching names return string_utils.resolve_matching_names(name_keys, list_of_strings)[1] - """ - Implementation specific. - """ + @staticmethod + def resolve_term_cfg(env: ManagerBasedEnv, term_name: str, term_cfg: ManagerTermBaseCfg, min_argc: int = 1): + """Resolve common attributes of a manager term configuration. - @abstractmethod - def _prepare_terms(self): - """Prepare terms information from the configuration object.""" - raise NotImplementedError - - """ - Helper functions. - """ - - def _resolve_common_term_cfg(self, term_name: str, term_cfg: ManagerTermBaseCfg, min_argc: int = 1): - """Resolve common term configuration. - - Usually, called by the :meth:`_prepare_terms` method to resolve common term configuration. + This function resolves the common attributes of a manager term configuration. It checks if the + term configuration is of type :class:`ManagerTermBaseCfg`, resolves the scene entity defined in the + term configuration, checks if the term function is callable, and verifies if the term function's + arguments are matched by the parameters. Note: By default, all term functions are expected to have at least one argument, which is the @@ -218,6 +209,7 @@ def _resolve_common_term_cfg(self, term_name: str, term_cfg: ManagerTermBaseCfg, required by the term function to be called correctly by the manager. Args: + env: The environment instance. term_name: The name of the term. term_cfg: The term configuration. min_argc: The minimum number of arguments required by the term function to be called correctly @@ -239,11 +231,14 @@ def _resolve_common_term_cfg(self, term_name: str, term_cfg: ManagerTermBaseCfg, for key, value in term_cfg.params.items(): # deal with string if isinstance(value, SceneEntityCfg): - # load the entity - try: - value.resolve(self._env.scene) - except ValueError as e: - raise ValueError(f"Error while parsing '{term_name}:{key}'. {e}") + # check if sim is playing and resolve the entity + # joint and body names are only available once the sim is playing + # hence, we do not resolve the entity if the sim is not playing + if env.sim.is_playing(): + try: + value.resolve(env.scene) + except ValueError as e: + raise ValueError(f"Error while parsing '{term_name}:{key}'. {e}") # log the entity for checking later msg = f"[{term_cfg.__class__.__name__}:{term_name}] Found entity '{value.name}'." if value.joint_ids is not None: @@ -266,7 +261,7 @@ def _resolve_common_term_cfg(self, term_name: str, term_cfg: ManagerTermBaseCfg, f"Configuration for the term '{term_name}' is not of type ManagerTermBase." f" Received: '{type(term_cfg.func)}'." ) - term_cfg.func = term_cfg.func(cfg=term_cfg, env=self._env) + term_cfg.func = term_cfg.func(cfg=term_cfg, env=env) # check if function is callable if not callable(term_cfg.func): raise AttributeError(f"The term '{term_name}' is not callable. Received: {term_cfg.func}") @@ -285,3 +280,24 @@ def _resolve_common_term_cfg(self, term_name: str, term_cfg: ManagerTermBaseCfg, f"The term '{term_name}' expects mandatory parameters: {args_without_defaults[min_argc:]}" f" and optional parameters: {args_with_defaults}, but received: {term_params}." ) + + """ + Implementation specific. + """ + + @abstractmethod + def _prepare_terms(self): + """Prepare terms information from the configuration object.""" + raise NotImplementedError + + """ + Helper functions. + """ + + def _resolve_common_term_cfg(self, term_name: str, term_cfg: ManagerTermBaseCfg, min_argc: int = 1): + """Resolve common attributes of a manager term configuration. + + Usually, called by the :meth:`_prepare_terms` method to resolve common term configuration. + It wraps the :meth:`resolve_term_cfg` method and passes the environment instance. + """ + ManagerBase.resolve_term_cfg(self._env, term_name, term_cfg, min_argc) From a120c535e97c63ab9e3f9393edd7073ddb3daf56 Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Mon, 7 Oct 2024 14:11:58 +0200 Subject: [PATCH 10/11] fixes format --- .../omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py index 1246609104..c0fb181221 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/mdp/events.py @@ -34,16 +34,12 @@ from omni.isaac.lab.envs import ManagerBasedEnv -def randomize_shape_color( - env: ManagerBasedEnv, - env_ids: torch.Tensor | None, - asset_cfg: SceneEntityCfg, -): +def randomize_shape_color(env: ManagerBasedEnv, env_ids: torch.Tensor | None, asset_cfg: SceneEntityCfg): """Randomize the color of a shape. This function randomizes the color of USD shapes created using :class:`omni.isaac.lab.sim.spawn.ShapeCfg` class. It modifies the attribute: "geometry/material/Shader.inputs:diffuseColor" under the prims - corresponding to the asset. + corresponding to the asset. If the attribute does not exist, the function errors out. """ # extract the used quantities (to enable type-hinting) asset: RigidObject = env.scene[asset_cfg.name] From 870ce8aff2948630b749f38abe585a90ee4f529a Mon Sep 17 00:00:00 2001 From: Mayank Mittal Date: Mon, 7 Oct 2024 14:21:39 +0200 Subject: [PATCH 11/11] fix direct task check --- .../omni/isaac/lab/envs/direct_marl_env.py | 9 +++------ .../omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py | 9 +++------ 2 files changed, 6 insertions(+), 12 deletions(-) diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py index 2d3ad68c6c..5196f172d5 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_marl_env.py @@ -114,8 +114,9 @@ def __init__(self, cfg: DirectMARLEnvCfg, render_mode: str | None = None, **kwar print("[INFO]: Scene manager: ", self.scene) # randomization at scene level - with Timer("[INFO]: Time taken for scene randomization", "scene_randomization"): - self._apply_scene_randomization() + if self.cfg.events: + with Timer("[INFO]: Time taken for scene randomization", "scene_randomization"): + self._apply_scene_randomization() # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning @@ -576,10 +577,6 @@ def _apply_scene_randomization(self): It must be called only before the simulation/physics is started. """ - # check if events exist - if not self.cfg.events: - return - # check if scene randomization is enabled applied_scene_randomization = False # iterate over all event terms diff --git a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py index b0d622e8e4..7508bff28d 100644 --- a/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py +++ b/source/extensions/omni.isaac.lab/omni/isaac/lab/envs/direct_rl_env.py @@ -119,8 +119,9 @@ def __init__(self, cfg: DirectRLEnvCfg, render_mode: str | None = None, **kwargs print("[INFO]: Scene manager: ", self.scene) # randomization at scene level - with Timer("[INFO]: Time taken for scene randomization", "scene_randomization"): - self._apply_scene_randomization() + if not self.cfg.events: + with Timer("[INFO]: Time taken for scene randomization", "scene_randomization"): + self._apply_scene_randomization() # set up camera viewport controller # viewport is not available in other rendering modes so the function will throw a warning @@ -518,10 +519,6 @@ def _apply_scene_randomization(self): It must be called only before the simulation/physics is started. """ - # check if events exist - if not self.cfg.events: - return - # check if scene randomization is enabled applied_scene_randomization = False # iterate over all event terms