From 1c92818464fd3f4c5dd6e360170873fd1f3329ce Mon Sep 17 00:00:00 2001 From: Octi Zhang Date: Sun, 29 Jun 2025 14:10:53 -0700 Subject: [PATCH] support composite obs space with proper min max specification in manager based env --- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 11 ++++ .../isaaclab/envs/manager_based_rl_env.py | 11 ++-- .../test_manager_based_rl_env_obs_spaces.py | 57 +++++++++++++++++++ 4 files changed, 76 insertions(+), 5 deletions(-) create mode 100644 source/isaaclab/test/envs/test_manager_based_rl_env_obs_spaces.py diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index cf769e34cfb..1ac95ccdbc8 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.40.11" +version = "0.X.0" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index 7dfe075a3a4..b1495435a0f 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,17 @@ Changelog --------- +0.X.0 (2025-06-29) +~~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added MangerBasedRLEnv support for composite gym observation spaces. +* A test for the composite gym observation spaces in ManagerBasedRLEnv is added to ensure that the observation spaces + are correctly configured base on the clip. + + 0.40.11 (2025-06-27) ~~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py index b91501b8dbd..ca6256e4a77 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_rl_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_rl_env.py @@ -333,10 +333,13 @@ def _configure_gym_env_spaces(self): if has_concatenated_obs: self.single_observation_space[group_name] = gym.spaces.Box(low=-np.inf, high=np.inf, shape=group_dim) else: - self.single_observation_space[group_name] = gym.spaces.Dict({ - term_name: gym.spaces.Box(low=-np.inf, high=np.inf, shape=term_dim) - for term_name, term_dim in zip(group_term_names, group_dim) - }) + group_term_cfgs = self.observation_manager._group_obs_term_cfgs[group_name] + for term_name, term_dim, term_cfg in zip(group_term_names, group_dim, group_term_cfgs): + low = -np.inf if term_cfg.clip is None else term_cfg.clip[0] + high = np.inf if term_cfg.clip is None else term_cfg.clip[1] + self.single_observation_space[group_name] = gym.spaces.Dict( + {term_name: gym.spaces.Box(low=low, high=high, shape=term_dim)} + ) # action space (unbounded since we don't impose any limits) action_dim = sum(self.action_manager.action_term_dim) self.single_action_space = gym.spaces.Box(low=-np.inf, high=np.inf, shape=(action_dim,)) diff --git a/source/isaaclab/test/envs/test_manager_based_rl_env_obs_spaces.py b/source/isaaclab/test/envs/test_manager_based_rl_env_obs_spaces.py new file mode 100644 index 00000000000..5ad2777cc44 --- /dev/null +++ b/source/isaaclab/test/envs/test_manager_based_rl_env_obs_spaces.py @@ -0,0 +1,57 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +"""Test texture randomization in the cartpole scene using pytest.""" + +from isaaclab.app import AppLauncher + +# launch omniverse app +simulation_app = AppLauncher(headless=True, enable_cameras=True).app + +import gymnasium as gym +import numpy as np + +import omni.usd +import pytest + +from isaaclab.envs import ManagerBasedRLEnv + +from isaaclab_tasks.manager_based.classic.cartpole.cartpole_camera_env_cfg import ( + CartpoleDepthCameraEnvCfg, + CartpoleRGBCameraEnvCfg, +) +from isaaclab_tasks.manager_based.locomotion.velocity.config.anymal_c.rough_env_cfg import AnymalCRoughEnvCfg + + +@pytest.mark.parametrize( + "env_cfg_cls", + [CartpoleRGBCameraEnvCfg, CartpoleDepthCameraEnvCfg, AnymalCRoughEnvCfg], + ids=["RGB", "Depth", "RayCaster"], +) +@pytest.mark.parametrize("device", ["cpu", "cuda"]) +def test_obs_space_follows_clip_contraint(env_cfg_cls, device): + """Ensure curriculum terms apply correctly after the fallback and replacement.""" + # new USD stage + omni.usd.get_context().new_stage() + + # configure the cartpole env + env_cfg = env_cfg_cls() + env_cfg.scene.num_envs = 2 # keep num_envs small for testing + env_cfg.observations.policy.concatenate_terms = False + env_cfg.sim.device = device + + env = ManagerBasedRLEnv(cfg=env_cfg) + for group_name, group_space in env.observation_space.spaces.items(): + for term_name, term_space in group_space.spaces.items(): + term_cfg = getattr(getattr(env_cfg.observations, group_name), term_name) + low = -np.inf if term_cfg.clip is None else term_cfg.clip[0] + high = np.inf if term_cfg.clip is None else term_cfg.clip[1] + assert isinstance( + term_space, gym.spaces.Box + ), f"Expected Box space for {term_name} in {group_name}, got {type(term_space)}" + assert np.all(term_space.low == low) + assert np.all(term_space.high == high) + + env.close()