Unverified Commit ab3f3a36 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Fixes environment closing and tests for task implementations (#231)

# Description

This MR fixes the test scripts inside the `omni.isaac.orbit_tasks`
extension. The tests were previously crashing since they weren't updated
to latest changes in the core framework.

Additionally, the tests helped in realizing that the environment did not
close properly, i.e. some managers do not get destroyed properly and
still hold references to certain scene entities. The MR now explicitly
calls all `del` operators over all the managers to delete them in the
right-order.

## Type of change

- Bug fix (non-breaking change which fixes an issue)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there

---------
Signed-off-by: 's avatarMayank Mittal <12863862+Mayankm96@users.noreply.github.com>
parent 990f7bbc
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.9.35"
version = "0.9.36"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.9.36 (2023-11-03)
~~~~~~~~~~~~~~~~~~~
Fixed
^^^^^
* Added explicit deleting of different managers in the :class:`omni.isaac.orbit.envs.BaseEnv` and
:class:`omni.isaac.orbit.envs.RLTaskEnv` classes. This is required since deleting the managers
is order-sensitive (many managers need to be deleted before the scene is deleted).
0.9.35 (2023-11-02)
~~~~~~~~~~~~~~~~~~~
......
......@@ -76,7 +76,9 @@ class BaseEnv:
else:
raise RuntimeError("Simulation context already exists. Cannot create a new one.")
# set camera view for "/OmniverseKit_Persp" camera
self.sim.set_camera_view(eye=self.cfg.viewer.eye, target=self.cfg.viewer.lookat)
# viewport is not available in other rendering modes so the function will throw a warning
if self.sim.render_mode >= self.sim.RenderMode.PARTIAL_RENDERING:
self.sim.set_camera_view(eye=self.cfg.viewer.eye, target=self.cfg.viewer.lookat)
# print useful information
print("[INFO]: Base environment:")
......@@ -187,6 +189,11 @@ class BaseEnv:
def close(self):
"""Cleanup for the environment."""
if not self._is_closed:
# destructor is order-sensitive
del self.action_manager
del self.observation_manager
del self.randomization_manager
del self.scene
# clear callbacks and instance
self.sim.clear_all_callbacks()
self.sim.clear_instance()
......
......@@ -285,6 +285,16 @@ class RLTaskEnv(BaseEnv, gym.Env):
f"Render mode '{mode}' is not supported. Please use: {self.metadata['render.modes']}."
)
def close(self):
if not self._is_closed:
# destructor is order-sensitive
del self.command_manager
del self.reward_manager
del self.termination_manager
del self.curriculum_manager
# call the parent class to close the environment
super().close()
"""
Implementation specifics.
"""
......
......@@ -8,7 +8,7 @@
from __future__ import annotations
import numpy as np
from scipy.interpolate import interpolate
import scipy.interpolate as interpolate
from typing import TYPE_CHECKING
from .utils import height_field_to_mesh
......@@ -69,7 +69,7 @@ def random_uniform_terrain(difficulty: float, cfg: hf_terrains_cfg.HfRandomUnifo
# create interpolation function for the sampled heights
x = np.linspace(0, cfg.size[0] * cfg.horizontal_scale, width_downsampled)
y = np.linspace(0, cfg.size[1] * cfg.horizontal_scale, length_downsampled)
func = interpolate.interp2d(y, x, height_field_downsampled, kind="linear")
func = interpolate.RectBivariateSpline(y, x, height_field_downsampled)
# interpolate the sampled heights to obtain the height field
x_upsampled = np.linspace(0, cfg.size[0] * cfg.horizontal_scale, width_pixels)
......
......@@ -150,7 +150,7 @@ class TerrainGenerator:
for index in range(self.cfg.num_cols):
sub_index = np.min(np.where(index / self.cfg.num_cols + 0.001 < np.cumsum(proportions))[0])
sub_indices.append(sub_index)
sub_indices = np.array(sub_indices, dtype=np.int)
sub_indices = np.array(sub_indices, dtype=np.int32)
# create a list of all terrain configs
sub_terrains_cfgs = list(self.cfg.sub_terrains.values())
......
# Copyright (c) 2022-2023, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script shows the issue with launching Isaac Sim application in headless mode.
On launching the application in headless mode, the application does not exit gracefully.
There are multiple warnings and errors that are printed on the console.
```
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/deps/isaacsim/check_app.py
```
Output:
```
[10.948s] Simulation App Startup Complete
[11.471s] Simulation App Shutting Down
...... [Warning] [carb] [Plugin: omni.spectree.delegate.plugin] Module /media/vulcan/packman-repo/chk/kit-sdk/105.1+release.129498.98d86eae.tc.linux-x86_64.release/exts/omni.usd_resolver/bin/libomni.spectree.delegate.plugin.so remained loaded after unload request
...... [Warning] [omni.core.ITypeFactory] Module /media/vulcan/packman-repo/chk/kit-sdk/105.1+release.129498.98d86eae.tc.linux-x86_64.release/exts/omni.graph.action/bin/libomni.graph.action.plugin.so remained loaded after unload request.
...... [Warning] [omni.core.ITypeFactory] Module /media/vulcan/packman-repo/chk/kit-sdk/105.1+release.129498.98d86eae.tc.linux-x86_64.release/exts/omni.activity.core/bin/libomni.activity.core.plugin.so remained loaded after unload request.
```
"""
from __future__ import annotations
from omni.isaac.kit import SimulationApp
if __name__ == "__main__":
app = SimulationApp({"headless": True})
app.close()
......@@ -11,9 +11,9 @@ and have the same image as the previous episode for the first few steps.
```
# run with cube
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/isaacsim/check_camera.py --scenario cube
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/deps/isaacsim/check_camera.py --scenario cube
# run with anymal
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/isaacsim/check_camera.py --scenario anymal
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/deps/isaacsim/check_camera.py --scenario anymal
```
"""
......
......@@ -15,7 +15,7 @@ Usage:
.. code-block:: bash
./orbit.sh -p source/extensions/omni.isaac.orbit/test/isaacsim/check_rep_texture_randomizer.py
./orbit.sh -p source/extensions/omni.isaac.orbit/test/deps/isaacsim/check_rep_texture_randomizer.py
"""
......
# Copyright (c) 2022-2023, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
# isort: off
import warnings
warnings.filterwarnings("ignore", category=DeprecationWarning)
# isort: on
import numpy as np
import scipy.interpolate as interpolate
import unittest
class TestScipyOperations(unittest.TestCase):
"""Tests for assuring scipy related operations used in Orbit."""
def test_interpolation(self):
"""Test scipy interpolation 2D method."""
# parameters
size = (10.0, 10.0)
horizontal_scale = 0.1
vertical_scale = 0.005
downsampled_scale = 0.2
noise_range = (-0.02, 0.1)
noise_step = 0.02
# switch parameters to discrete units
# -- horizontal scale
width_pixels = int(size[0] / horizontal_scale)
length_pixels = int(size[1] / horizontal_scale)
# -- downsampled scale
width_downsampled = int(size[0] / downsampled_scale)
length_downsampled = int(size[1] / downsampled_scale)
# -- height
height_min = int(noise_range[0] / vertical_scale)
height_max = int(noise_range[1] / vertical_scale)
height_step = int(noise_step / vertical_scale)
# create range of heights possible
height_range = np.arange(height_min, height_max + height_step, height_step)
# sample heights randomly from the range along a grid
height_field_downsampled = np.random.choice(height_range, size=(width_downsampled, length_downsampled))
# create interpolation function for the sampled heights
x = np.linspace(0, size[0] * horizontal_scale, width_downsampled)
y = np.linspace(0, size[1] * horizontal_scale, length_downsampled)
# interpolate the sampled heights to obtain the height field
x_upsampled = np.linspace(0, size[0] * horizontal_scale, width_pixels)
y_upsampled = np.linspace(0, size[1] * horizontal_scale, length_pixels)
# -- method 1: interp2d (this will be deprecated in the future 1.13 release)
func_interp2d = interpolate.interp2d(y, x, height_field_downsampled, kind="cubic")
z_upsampled_interp2d = func_interp2d(y_upsampled, x_upsampled)
# -- method 2: RectBivariateSpline (alternate to interp2d)
func_RectBiVariate = interpolate.RectBivariateSpline(y, x, height_field_downsampled)
z_upsampled_RectBivariant = func_RectBiVariate(y_upsampled, x_upsampled)
# -- method 3: RegularGridInterpolator (recommended from scipy but slow!)
# Ref: https://github.com/scipy/scipy/issues/18010
func_RegularGridInterpolator = interpolate.RegularGridInterpolator(
(y, x), height_field_downsampled, method="cubic"
)
yy_upsampled, xx_upsampled = np.meshgrid(y_upsampled, x_upsampled, indexing="ij", sparse=True)
z_upsampled_RegularGridInterpolator = func_RegularGridInterpolator((yy_upsampled, xx_upsampled))
# check if the interpolated height field is the same as the sampled height field
np.testing.assert_allclose(z_upsampled_interp2d, z_upsampled_RectBivariant, atol=1e-14)
np.testing.assert_allclose(z_upsampled_RectBivariant, z_upsampled_RegularGridInterpolator, atol=1e-14)
np.testing.assert_allclose(z_upsampled_RegularGridInterpolator, z_upsampled_interp2d, atol=1e-14)
if __name__ == "__main__":
unittest.main()
......@@ -18,10 +18,10 @@ class TestRobomimicDataCollector(unittest.TestCase):
def test_basic_flushing(self):
"""Adds random data into the collector and checks saving of the data."""
# name of the environment (needed by robomimic)
task_name = "Isaac-Franka-Lift-v0"
task_name = "My-Task-v0"
# specify directory for logging experiments
test_dir = os.path.dirname(os.path.abspath(__file__))
log_dir = os.path.join(test_dir, "logs", "demos")
log_dir = os.path.join(test_dir, "output", "demos")
# name of the file to save data
filename = "hdf_dataset.hdf5"
# number of episodes to collect
......
......@@ -3,18 +3,18 @@
#
# SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
from __future__ import annotations
"""Launch Isaac Sim Simulator first."""
import os
from omni.isaac.kit import SimulationApp
from omni.isaac.orbit.app import AppLauncher
# launch the simulator
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
config = {"headless": True}
simulation_app = SimulationApp(config, experience=app_experience)
app_launcher = AppLauncher(headless=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
......@@ -23,10 +23,14 @@ simulation_app = SimulationApp(config, experience=app_experience)
import gym
import gym.envs
import torch
import traceback
import unittest
import carb
import omni.usd
from omni.isaac.orbit.envs import RLTaskEnv, RLTaskEnvCfg
import omni.isaac.orbit_tasks # noqa: F401
from omni.isaac.orbit_tasks.utils.parse_cfg import parse_env_cfg
......@@ -35,34 +39,35 @@ class TestEnvironments(unittest.TestCase):
"""Test cases for all registered environments."""
@classmethod
def tearDownClass(cls):
"""Closes simulator after running all test fixtures."""
simulation_app.close()
def setUp(self) -> None:
self.num_envs = 512
self.headless = simulation_app.config["headless"]
def setUpClass(cls):
# acquire all Isaac environments names
self.registered_tasks = list()
cls.registered_tasks = list()
for task_spec in gym.envs.registry.all():
if "Isaac" in task_spec.id:
self.registered_tasks.append(task_spec.id)
cls.registered_tasks.append(task_spec.id)
# sort environments by name
self.registered_tasks.sort()
cls.registered_tasks.sort()
# print all existing task names
print(">>> All registered environments:", self.registered_tasks)
print(">>> All registered environments:", cls.registered_tasks)
def setUp(self) -> None:
# common parameters
self.num_envs = 512
self.use_gpu = True
def test_random_actions(self):
"""Run random actions and check environments return valid signals."""
for task_name in self.registered_tasks:
print(f">>> Running test for environment: {task_name}")
# create a new stage
omni.usd.get_context().new_stage()
# parse configuration
env_cfg = parse_env_cfg(task_name, use_gpu=True, num_envs=self.num_envs)
env_cfg: RLTaskEnvCfg = parse_env_cfg(task_name, use_gpu=self.use_gpu, num_envs=self.num_envs)
# note: we don't want to shutdown the app on stop during the tests since we reload the stage
env_cfg.sim.shutdown_app_on_stop = False
# create environment
env = gym.make(task_name, cfg=env_cfg)
env: RLTaskEnv = gym.make(task_name, cfg=env_cfg)
# reset environment
obs = env.reset()
......@@ -74,12 +79,10 @@ class TestEnvironments(unittest.TestCase):
# sample actions from -1 to 1
actions = 2 * torch.rand((env.num_envs, env.action_space.shape[0]), device=env.device) - 1
# apply actions
obs, rew, dones, info = env.step(actions)
transition = env.step(actions)
# check signals
self.assertTrue(self._check_valid_tensor(obs))
self.assertTrue(self._check_valid_tensor(rew))
self.assertTrue(self._check_valid_tensor(dones))
self.assertTrue(self._check_valid_tensor(info))
for data in transition:
self.assertTrue(self._check_valid_tensor(data), msg=f"Invalid data: {data}")
# close the environment
print(f">>> Closing environment: {task_name}")
......@@ -106,7 +109,7 @@ class TestEnvironments(unittest.TestCase):
for value in data.values():
if isinstance(value, dict):
return TestEnvironments._check_valid_tensor(value)
else:
elif isinstance(value, torch.Tensor):
valid_tensor = valid_tensor and not torch.any(torch.isnan(value))
return valid_tensor
else:
......@@ -114,4 +117,12 @@ class TestEnvironments(unittest.TestCase):
if __name__ == "__main__":
unittest.main()
try:
unittest.main()
except Exception as err:
carb.log_error(err)
carb.log_error(traceback.format_exc())
raise
finally:
# close sim app
simulation_app.close()
......@@ -9,12 +9,12 @@ from __future__ import annotations
import os
from omni.isaac.kit import SimulationApp
from omni.isaac.orbit.app import AppLauncher
# launch the simulator
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.render.kit"
config = {"headless": True}
simulation_app = SimulationApp(config, experience=app_experience)
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
app_launcher = AppLauncher(headless=True, offscreen_render=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
......@@ -22,8 +22,14 @@ simulation_app = SimulationApp(config, experience=app_experience)
import gym
import os
import torch
import traceback
import unittest
import carb
import omni.usd
from omni.isaac.orbit.envs import RLTaskEnv, RLTaskEnvCfg
import omni.isaac.contrib_tasks # noqa: F401
import omni.isaac.orbit_tasks # noqa: F401
from omni.isaac.orbit_tasks.utils import parse_env_cfg
......@@ -33,41 +39,41 @@ class TestRecordVideoWrapper(unittest.TestCase):
"""Test recording videos using the RecordVideo wrapper."""
@classmethod
def tearDownClass(cls):
"""Closes simulator after running all test fixtures."""
simulation_app.close()
def setUpClass(cls):
# acquire all Isaac environments names
cls.registered_tasks = list()
for task_spec in gym.envs.registry.all():
if "Isaac" in task_spec.id:
cls.registered_tasks.append(task_spec.id)
# sort environments by name
cls.registered_tasks.sort()
# print all existing task names
print(">>> All registered environments:", cls.registered_tasks)
# directory to save videos
cls.videos_dir = os.path.join(os.path.dirname(__file__), "output", "videos")
def setUp(self) -> None:
# common parameters
self.num_envs = 64
self.use_gpu = True
self.headless = simulation_app.config["headless"]
# directory to save videos
self.videos_dir = os.path.join(os.path.dirname(__file__), "videos")
# video parameters
self.step_trigger = lambda step: step % 225 == 0
self.video_length = 200
# acquire all Isaac environments names
self.registered_tasks = list()
for task_spec in gym.envs.registry.all():
if "Isaac" in task_spec.id:
self.registered_tasks.append(task_spec.id)
# sort environments by name
self.registered_tasks.sort()
# print all existing task names
print(">>> All registered environments:", self.registered_tasks)
def test_record_video(self):
"""Run random actions agent with recording of videos."""
import omni.usd
for task_name in self.registered_tasks:
print(f">>> Running test for environment: {task_name}")
# create a new stage
omni.usd.get_context().new_stage()
# parse configuration
env_cfg = parse_env_cfg(task_name, use_gpu=self.use_gpu, num_envs=self.num_envs)
env_cfg: RLTaskEnvCfg = parse_env_cfg(task_name, use_gpu=self.use_gpu, num_envs=self.num_envs)
# note: we don't want to shutdown the app on stop during the tests since we reload the stage
env_cfg.sim.shutdown_app_on_stop = False
# create environment
env = gym.make(task_name, cfg=env_cfg)
env: RLTaskEnv = gym.make(task_name, cfg=env_cfg)
# directory to save videos
videos_dir = os.path.join(self.videos_dir, task_name)
......@@ -83,16 +89,21 @@ class TestRecordVideoWrapper(unittest.TestCase):
# compute zero actions
actions = 2 * torch.rand((env.num_envs, env.action_space.shape[0]), device=env.device) - 1
# apply actions
_, _, _, _ = env.step(actions)
_ = env.step(actions)
# render environment
env.render(mode="human")
# check if simulator is stopped
if env.unwrapped.sim.is_stopped():
break
# close the simulator
env.close()
if __name__ == "__main__":
unittest.main()
try:
unittest.main()
except Exception as err:
carb.log_error(err)
carb.log_error(traceback.format_exc())
raise
finally:
# close sim app
simulation_app.close()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment