Skip to content

Commit 1c92818

Browse files
committed
support composite obs space with proper min max specification in manager based env
1 parent 3d6f55b commit 1c92818

File tree

4 files changed

+76
-5
lines changed

4 files changed

+76
-5
lines changed

source/isaaclab/config/extension.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
[package]
22

33
# Note: Semantic Versioning is used: https://semver.org/
4-
version = "0.40.11"
4+
version = "0.X.0"
55

66
# Description
77
title = "Isaac Lab framework for Robot Learning"

source/isaaclab/docs/CHANGELOG.rst

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,17 @@
11
Changelog
22
---------
33

4+
0.X.0 (2025-06-29)
5+
~~~~~~~~~~~~~~~~~~~~
6+
7+
Added
8+
^^^^^
9+
10+
* Added MangerBasedRLEnv support for composite gym observation spaces.
11+
* A test for the composite gym observation spaces in ManagerBasedRLEnv is added to ensure that the observation spaces
12+
are correctly configured base on the clip.
13+
14+
415
0.40.11 (2025-06-27)
516
~~~~~~~~~~~~~~~~~~~~
617

source/isaaclab/isaaclab/envs/manager_based_rl_env.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -333,10 +333,13 @@ def _configure_gym_env_spaces(self):
333333
if has_concatenated_obs:
334334
self.single_observation_space[group_name] = gym.spaces.Box(low=-np.inf, high=np.inf, shape=group_dim)
335335
else:
336-
self.single_observation_space[group_name] = gym.spaces.Dict({
337-
term_name: gym.spaces.Box(low=-np.inf, high=np.inf, shape=term_dim)
338-
for term_name, term_dim in zip(group_term_names, group_dim)
339-
})
336+
group_term_cfgs = self.observation_manager._group_obs_term_cfgs[group_name]
337+
for term_name, term_dim, term_cfg in zip(group_term_names, group_dim, group_term_cfgs):
338+
low = -np.inf if term_cfg.clip is None else term_cfg.clip[0]
339+
high = np.inf if term_cfg.clip is None else term_cfg.clip[1]
340+
self.single_observation_space[group_name] = gym.spaces.Dict(
341+
{term_name: gym.spaces.Box(low=low, high=high, shape=term_dim)}
342+
)
340343
# action space (unbounded since we don't impose any limits)
341344
action_dim = sum(self.action_manager.action_term_dim)
342345
self.single_action_space = gym.spaces.Box(low=-np.inf, high=np.inf, shape=(action_dim,))
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2+
# All rights reserved.
3+
#
4+
# SPDX-License-Identifier: BSD-3-Clause
5+
6+
"""Test texture randomization in the cartpole scene using pytest."""
7+
8+
from isaaclab.app import AppLauncher
9+
10+
# launch omniverse app
11+
simulation_app = AppLauncher(headless=True, enable_cameras=True).app
12+
13+
import gymnasium as gym
14+
import numpy as np
15+
16+
import omni.usd
17+
import pytest
18+
19+
from isaaclab.envs import ManagerBasedRLEnv
20+
21+
from isaaclab_tasks.manager_based.classic.cartpole.cartpole_camera_env_cfg import (
22+
CartpoleDepthCameraEnvCfg,
23+
CartpoleRGBCameraEnvCfg,
24+
)
25+
from isaaclab_tasks.manager_based.locomotion.velocity.config.anymal_c.rough_env_cfg import AnymalCRoughEnvCfg
26+
27+
28+
@pytest.mark.parametrize(
29+
"env_cfg_cls",
30+
[CartpoleRGBCameraEnvCfg, CartpoleDepthCameraEnvCfg, AnymalCRoughEnvCfg],
31+
ids=["RGB", "Depth", "RayCaster"],
32+
)
33+
@pytest.mark.parametrize("device", ["cpu", "cuda"])
34+
def test_obs_space_follows_clip_contraint(env_cfg_cls, device):
35+
"""Ensure curriculum terms apply correctly after the fallback and replacement."""
36+
# new USD stage
37+
omni.usd.get_context().new_stage()
38+
39+
# configure the cartpole env
40+
env_cfg = env_cfg_cls()
41+
env_cfg.scene.num_envs = 2 # keep num_envs small for testing
42+
env_cfg.observations.policy.concatenate_terms = False
43+
env_cfg.sim.device = device
44+
45+
env = ManagerBasedRLEnv(cfg=env_cfg)
46+
for group_name, group_space in env.observation_space.spaces.items():
47+
for term_name, term_space in group_space.spaces.items():
48+
term_cfg = getattr(getattr(env_cfg.observations, group_name), term_name)
49+
low = -np.inf if term_cfg.clip is None else term_cfg.clip[0]
50+
high = np.inf if term_cfg.clip is None else term_cfg.clip[1]
51+
assert isinstance(
52+
term_space, gym.spaces.Box
53+
), f"Expected Box space for {term_name} in {group_name}, got {type(term_space)}"
54+
assert np.all(term_space.low == low)
55+
assert np.all(term_space.high == high)
56+
57+
env.close()

0 commit comments

Comments
 (0)