Unverified Commit f733830f authored by AutonomousHansen's avatar AutonomousHansen Committed by GitHub

Renames `VIEWPORT_ENABLED` to `OFFSCREEN_RENDERING` for clarity (#167)

# Description

- Made SimulationContext correctly report RenderMode for streaming
- Changed language about HEADLESS in RenderMode to instead be NO_GUI,
because headlessness still requires rendering when livestreaming is
active, whereas NO_GUI is unambiguous. Also did some reordering of
docstrings for clarity.
- Removed unnecessary RENDER and VIEWPORT class vars from LauncherApp,
now that this signal is being taken from SimulationContext.

I will propagate this change to all standalone scripts/update docs once
I have conceptual approval.

Fixes #90, #145 

## Type of change

- New feature (non-breaking change which adds functionality)
- This change requires a documentation update

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [x] 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

---------
Signed-off-by: 's avatarAutonomousHansen <50837800+AutonomousHansen@users.noreply.github.com>
Co-authored-by: 's avatarMayank Mittal <mittalma@leggedrobotics.com>
parent 96737252
......@@ -32,6 +32,7 @@
**/output/*
**/outputs/*
**/videos/*
docker/artifacts/
*.tmp
# Isaac-Sim packman
......
......@@ -15,6 +15,17 @@ For example, here is how you would wrap an environment to enforce that reset is
.. code-block:: python
"""Launch Isaac Sim Simulator first."""
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app in headless mode
app_launcher = AppLauncher(headless=True)
simulation_app = app_launcher.app
"""Rest everything follows."""
import gym
import omni.isaac.orbit_envs # noqa: F401
......@@ -22,7 +33,7 @@ For example, here is how you would wrap an environment to enforce that reset is
# create base environment
cfg = load_default_env_cfg("Isaac-Reach-Franka-v0")
env = gym.make("Isaac-Reach-Franka-v0", cfg=cfg, render=True)
env = gym.make("Isaac-Reach-Franka-v0", cfg=cfg)
# wrap environment to enforce that reset is called before step
env = gym.wrappers.OrderEnforcing(env)
......@@ -41,23 +52,12 @@ To use the wrapper, you need to first install ``ffmpeg``. On Ubuntu, you can ins
sudo apt-get install ffmpeg
The :class:`IsaacEnv` supports different rendering modes: "human" and "rgb_array". The "human" mode
is used when you want to render the environment to the screen. The "rgb_array" mode is used when you want
to get the rendered image as a numpy array. However, the "rgb_array" mode is allowed only when viewport
is enabled. This can be done by setting the ``viewport`` argument to ``True`` when creating the environment.
.. code-block:: python
import gym
import omni.isaac.orbit_envs # noqa: F401
from omni.isaac.orbit_envs.utils import load_default_env_cfg
The :class:`omni.isaac.orbit.envs.RlEnv` supports the rendering modes:
# create base environment
cfg = load_default_env_cfg("Isaac-Reach-Franka-v0")
env = gym.make("Isaac-Reach-Franka-v0", cfg=cfg, render=True, viewport=True)
# wrap environment to enforce that reset is called before step
env = gym.wrappers.OrderEnforcing(env)
* **"human"**: When you want to render the environment to the screen. It does not return any image.
* **"rgb_array"**: When you want to get the rendered image as a numpy array. It returns the image as a numpy array.
This mode is only possible when viewport is enabled, i.e. either the GUI window is open or off-screen rendering flag
is enabled.
.. attention::
......@@ -67,32 +67,44 @@ is enabled. This can be done by setting the ``viewport`` argument to ``True`` wh
We notice the following performance in different rendering modes with the ``Isaac-Reach-Franka-v0`` environment
using an RTX 3090 GPU:
* Headless execution without viewport enabled: ~65,000 FPS
* Headless execution with viewport enabled: ~57,000 FPS
* Non-headless execution (i.e. with GUI): ~13,000 FPS
* No GUI execution without off-screen rendering enabled: ~65,000 FPS
* No GUI execution with off-screen enabled: ~57,000 FPS
* GUI execution with full rendering: ~13,000 FPS
The viewport camera used for rendering is the default camera in the scene called ``"/OmniverseKit_Persp"``.
The camera's pose and image resolution can be configured through the
:class:`omni.isaac.orbit_env.isaac_env_cfg.ViewerCfg` class.
:class:`omni.isaac.orbit.envs.base_env_cfg.ViewerCfg` class.
.. dropdown:: :fa:`eye,mr-1` Default parameters of the :class:`ViewerCfg` in the ``isaac_env_cfg.py`` file:
.. dropdown:: :fa:`eye,mr-1` Default parameters of the :class:`ViewerCfg` in the ``base_env_cfg.py`` file:
.. literalinclude:: ../../../source/extensions/omni.isaac.orbit_envs/omni/isaac/orbit_envs/isaac_env_cfg.py
.. literalinclude:: ../../../source/extensions/omni.isaac.orbit/omni/isaac/orbit/envs/base_env_cfg.py
:language: python
:lines: 37-52
:lines: 23-38
:linenos:
:lineno-start: 37
:lineno-start: 31
After adjusting the parameters, you can record videos by wrapping the environment with the
:class:`gym.wrappers.RecordVideo <gym:RecordVideo>` wrapper. As an example, the following code
records a video of the ``Isaac-Reach-Franka-v0`` environment for 200 steps, and saves it in the
``videos`` folder at a step interval of 1500 steps.
:class:`gym.wrappers.RecordVideo <gym:RecordVideo>` wrapper and enabling the off-screen rendering
flag. As an example, the following code records a video of the ``Isaac-Reach-Franka-v0`` environment
for 200 steps, and saves it in the ``videos`` folder at a step interval of 1500 steps.
.. code:: python
"""Launch Isaac Sim Simulator first."""
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app in headless mode with off-screen rendering
app_launcher = AppLauncher(headless=True, offscreen_render=True)
simulation_app = app_launcher.app
"""Rest everything follows."""
import gym
# adjust camera resolution and pose
......@@ -100,7 +112,7 @@ records a video of the ``Isaac-Reach-Franka-v0`` environment for 200 steps, and
env_cfg.viewer.eye = (1.0, 1.0, 1.0)
env_cfg.viewer.lookat = (0.0, 0.0, 0.0)
# create isaac-env instance
env = gym.make(task_name, cfg=env_cfg, render=headless, viewport=True)
env = gym.make(task_name, cfg=env_cfg)
# wrap for video recording
video_kwargs = {
"video_folder": "videos",
......
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.9.19"
version = "0.9.20"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.9.20 (2023-10-03)
~~~~~~~~~~~~~~~~~~~
Fixed
^^^^^
* Changed naming in :class:`omni.isaac.orbit.sim.SimulationContext.RenderMode` to use ``NO_GUI_OR_RENDERING``
and ``NO_RENDERING`` instead of ``HEADLESS`` for clarity.
* Changed :class:`omni.isaac.orbit.sim.SimulationContext` to be capable of handling livestreaming and
offscreen rendering.
* Changed :class:`omni.isaac.orbit.app.AppLauncher` envvar ``VIEWPORT_RECORD`` to the more descriptive
``OFFSCREEN_RENDER``.
0.9.19 (2023-10-25)
~~~~~~~~~~~~~~~~~~~
......@@ -173,6 +187,8 @@ Fixed
* Fixed the boundedness of class objects that register callbacks into the simulator.
These include devices, :class:`AssetBase`, :class:`SensorBase` and :class:`CommandGenerator`.
The fix ensures that object gets deleted when the user deletes the object.
0.9.7 (2023-09-26)
~~~~~~~~~~~~~~~~~~
......
......@@ -28,11 +28,13 @@ class ViewerCfg:
"""Initial camera position (in m). Default is (7.5, 7.5, 7.5)."""
lookat: Tuple[float, float, float] = (0.0, 0.0, 0.0)
"""Initial camera target position (in m). Default is (0.0, 0.0, 0.0)."""
cam_prim_path: str = "/OmniverseKit_Persp"
"""The camera prim path to record images from. Default is "/OmniverseKit_Persp", which is the
default camera in the default viewport.
"""
resolution: Tuple[int, int] = (1280, 720)
"""The resolution (width, height) of the default viewport (in pixels). Default is (1280, 720).
This is the resolution of the camera "/OmniverseKit_Persp", that is used in default viewport.
The camera is also used for rendering RGB images of the simulation.
"""The resolution (width, height) of the camera specified using :attr:`cam_prim_path`.
Default is (1280, 720).
"""
......
......@@ -110,10 +110,10 @@ class RLEnv(BaseEnv, gym.Env):
# extend UI elements
# we need to do this here after all the managers are initialized
# this is because they dictate the sensors and commands right now
if not self.sim.is_headless():
if self.sim.has_gui():
self._build_ui()
else:
# if headless, then we don't need to store the window
# if no window, then we don't need to store the window
self._orbit_window = None
self._orbit_window_elements = dict()
......@@ -222,6 +222,10 @@ class RLEnv(BaseEnv, gym.Env):
self.sim.step(render=False)
# update buffers at sim dt
self.scene.update(dt=self.physics_dt)
# perform rendering if gui is enabled
if self.sim.has_gui():
self.sim.render()
# post-step:
# -- update env counters (used for curriculum generation)
self.episode_length_buf += 1 # step in current episode (per env)
......@@ -257,11 +261,12 @@ class RLEnv(BaseEnv, gym.Env):
mode: The mode to render with. Defaults to "human".
Returns:
The rendered image as a numpy array if mode is "rgb_array" and offscreen
rendering is enabled.
The rendered image as a numpy array if mode is "rgb_array".
Raises:
RuntimeError: If mode is set to "rgb_data" and offscreen rendering is disabled.
RuntimeError: If mode is set to "rgb_data" and simulation render mode does not support it.
In this case, the simulation render mode must be set to ``RenderMode.PARTIAL_RENDERING``
or ``RenderMode.FULL_RENDERING``.
NotImplementedError: If an unsupported rendering mode is specified.
"""
# run a rendering step of the simulator
......@@ -270,28 +275,34 @@ class RLEnv(BaseEnv, gym.Env):
if mode == "human":
return None
elif mode == "rgb_array":
return np.zeros((self.cfg.viewer.resolution[1], self.cfg.viewer.resolution[0], 3), dtype=np.uint8)
# TODO: Add support to allow video recording!!
# # check if viewport is enabled -- if not, then complain because we won't get any data
# if not self.offscreen_render:
# raise RuntimeError(
# f"Cannot render '{mode}' when offscreen rendering is False. Please check the provided"
# "arguments to the environment class at initialization."
# )
# # check if viewport is enabled before creating render product
# import omni.replicator.core as rep
# # create render product
# self._render_product = rep.create.render_product("/OmniverseKit_Persp", self.cfg.viewer.resolution)
# # create rgb annotator -- used to read data from the render product
# self._rgb_annotator = rep.AnnotatorRegistry.get_annotator("rgb", device="cpu")
# self._rgb_annotator.attach([self._render_product])
# # obtain the rgb data
# rgb_data = self._rgb_annotator.get_data()
# # convert to numpy array
# rgb_data = np.frombuffer(rgb_data, dtype=np.uint8).reshape(*rgb_data.shape)
# # return the rgb data
# return rgb_data[:, :, :3]
# check that if any render could have happened
if self.sim.render_mode.value < self.sim.RenderMode.PARTIAL_RENDERING.value:
raise RuntimeError(
f"Cannot render '{mode}' when the simulation render mode is '{self.sim.render_mode.name}'."
f" Please set the simulation render mode to '{self.sim.RenderMode.PARTIAL_RENDERING.name}' or "
f" '{self.sim.RenderMode.FULL_RENDERING.name}'."
)
# create the annotator if it does not exist
if not hasattr(self, "_rgb_annotator"):
import omni.replicator.core as rep
# create render product
self._render_product = rep.create.render_product(
self.cfg.viewer.cam_prim_path, self.cfg.viewer.resolution
)
# create rgb annotator -- used to read data from the render product
self._rgb_annotator = rep.AnnotatorRegistry.get_annotator("rgb", device="cpu")
self._rgb_annotator.attach([self._render_product])
# obtain the rgb data
rgb_data = self._rgb_annotator.get_data()
# convert to numpy array
rgb_data = np.frombuffer(rgb_data, dtype=np.uint8).reshape(*rgb_data.shape)
# return the rgb data
# note: initially the renerer is warming up and returns empty data
if rgb_data.size == 0:
return np.zeros((self.cfg.viewer.resolution[1], self.cfg.viewer.resolution[0], 3), dtype=np.uint8)
else:
return rgb_data[:, :, :3]
else:
raise NotImplementedError(
f"Render mode '{mode}' is not supported. Please use: {self.metadata['render.modes']}."
......
......@@ -118,7 +118,7 @@ def main():
break
# If simulation is paused, then skip.
if not sim.is_playing():
sim.step(render=app_launcher.RENDER)
sim.step()
continue
# reset
if count % 50 == 0:
......@@ -149,7 +149,7 @@ def main():
# write data to sim
scene.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# read data from sim
scene.update(sim_dt)
# update sim-time
......
......@@ -95,7 +95,7 @@ class TestSimulationContext(unittest.TestCase):
sim = SimulationContext()
# check default render mode
self.assertEqual(sim.render_mode, sim.RenderMode.HEADLESS)
self.assertEqual(sim.render_mode, sim.RenderMode.NO_GUI_OR_RENDERING)
def test_boundedness(self):
"""Test that the boundedness of the simulation context remains constant.
......
......@@ -113,8 +113,6 @@ class RslRlVecEnvWrapper(gym.Wrapper):
def step(self, actions: torch.Tensor) -> VecEnvStepReturn: # noqa: D102
# record step information
obs_dict, rew, dones, extras = self.env.step(actions)
# render the environment to allow for visualization
self.env.render()
# return step information
obs = obs_dict["policy"]
extras["observations"] = obs_dict
......
......@@ -133,7 +133,7 @@ def main():
robot.set_joint_position_target(actions)
robot.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# update buffers
robot.update(sim_dt)
# update sim-time
......
......@@ -159,7 +159,7 @@ def main():
# Simulate physics
while simulation_app.is_running():
# Step simulation
sim.step(render=app_launcher.RENDER)
sim.step()
# Update camera data
camera.update(dt=0.0)
......
......@@ -142,7 +142,7 @@ def main():
robot.set_joint_position_target(actions)
robot.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# update sim-time
sim_time += sim_dt
ep_step_count += 1
......
......@@ -188,7 +188,7 @@ def main():
robot.set_joint_position_target(joint_pos_des, arm_joint_ids)
robot.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
......
......@@ -115,7 +115,7 @@ def main():
robot.set_joint_position_target(robot.data.default_joint_pos.clone())
robot.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
......
......@@ -158,7 +158,7 @@ def main():
robot.set_joint_position_target(actions[:, 3:], joint_ids=[3, 4, 5, 6, 7, 8, 9, 10, 11])
robot.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# update sim-time
sim_time += sim_dt
ep_step_count += 1
......
......@@ -173,7 +173,7 @@ def main():
break
# If simulation is paused, then skip.
if not sim.is_playing():
sim.step(render=app_launcher.RENDER)
sim.step()
continue
# reset
if count % 350 == 0:
......@@ -193,7 +193,7 @@ def main():
# step simulation
# FIXME: this is needed for lula to update the buffers!
# the bug has been reported to the lula team
sim.step(render=app_launcher.RENDER)
sim.step()
# set the controller commands
rmp_controller.set_command(rmp_commands)
# compute the joint commands
......@@ -225,7 +225,7 @@ def main():
# apply actions
robot.apply_action(robot_actions)
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
......
......@@ -112,7 +112,7 @@ def main():
break
# If simulation is paused, then skip.
if not sim.is_playing():
sim.step(render=app_launcher.RENDER)
sim.step()
continue
# reset
if count % 50 == 0:
......@@ -143,7 +143,7 @@ def main():
# write data to sim
scene.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# read data from sim
scene.update(sim_dt)
# update sim-time
......
......@@ -112,7 +112,7 @@ def main():
# apply sim data
rigid_object.write_data_to_sim()
# perform step
sim.step(render=app_launcher.RENDER)
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
......
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