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 @@ ...@@ -32,6 +32,7 @@
**/output/* **/output/*
**/outputs/* **/outputs/*
**/videos/* **/videos/*
docker/artifacts/
*.tmp *.tmp
# Isaac-Sim packman # Isaac-Sim packman
......
...@@ -15,6 +15,17 @@ For example, here is how you would wrap an environment to enforce that reset is ...@@ -15,6 +15,17 @@ For example, here is how you would wrap an environment to enforce that reset is
.. code-block:: python .. 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 gym
import omni.isaac.orbit_envs # noqa: F401 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 ...@@ -22,7 +33,7 @@ For example, here is how you would wrap an environment to enforce that reset is
# create base environment # create base environment
cfg = load_default_env_cfg("Isaac-Reach-Franka-v0") 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 # wrap environment to enforce that reset is called before step
env = gym.wrappers.OrderEnforcing(env) env = gym.wrappers.OrderEnforcing(env)
...@@ -41,23 +52,12 @@ To use the wrapper, you need to first install ``ffmpeg``. On Ubuntu, you can ins ...@@ -41,23 +52,12 @@ To use the wrapper, you need to first install ``ffmpeg``. On Ubuntu, you can ins
sudo apt-get install ffmpeg sudo apt-get install ffmpeg
The :class:`IsaacEnv` supports different rendering modes: "human" and "rgb_array". The "human" mode The :class:`omni.isaac.orbit.envs.RlEnv` supports the rendering modes:
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
# create base environment * **"human"**: When you want to render the environment to the screen. It does not return any image.
cfg = load_default_env_cfg("Isaac-Reach-Franka-v0") * **"rgb_array"**: When you want to get the rendered image as a numpy array. It returns the image as a numpy array.
env = gym.make("Isaac-Reach-Franka-v0", cfg=cfg, render=True, viewport=True) This mode is only possible when viewport is enabled, i.e. either the GUI window is open or off-screen rendering flag
# wrap environment to enforce that reset is called before step is enabled.
env = gym.wrappers.OrderEnforcing(env)
.. attention:: .. attention::
...@@ -67,32 +67,44 @@ is enabled. This can be done by setting the ``viewport`` argument to ``True`` wh ...@@ -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 We notice the following performance in different rendering modes with the ``Isaac-Reach-Franka-v0`` environment
using an RTX 3090 GPU: using an RTX 3090 GPU:
* Headless execution without viewport enabled: ~65,000 FPS * No GUI execution without off-screen rendering enabled: ~65,000 FPS
* Headless execution with viewport enabled: ~57,000 FPS * No GUI execution with off-screen enabled: ~57,000 FPS
* Non-headless execution (i.e. with GUI): ~13,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 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 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 :language: python
:lines: 37-52 :lines: 23-38
:linenos: :linenos:
:lineno-start: 37 :lineno-start: 31
After adjusting the parameters, you can record videos by wrapping the environment with the 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 :class:`gym.wrappers.RecordVideo <gym:RecordVideo>` wrapper and enabling the off-screen rendering
records a video of the ``Isaac-Reach-Franka-v0`` environment for 200 steps, and saves it in the flag. As an example, the following code records a video of the ``Isaac-Reach-Franka-v0`` environment
``videos`` folder at a step interval of 1500 steps. for 200 steps, and saves it in the ``videos`` folder at a step interval of 1500 steps.
.. code:: python .. 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 import gym
# adjust camera resolution and pose # adjust camera resolution and pose
...@@ -100,7 +112,7 @@ records a video of the ``Isaac-Reach-Franka-v0`` environment for 200 steps, and ...@@ -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.eye = (1.0, 1.0, 1.0)
env_cfg.viewer.lookat = (0.0, 0.0, 0.0) env_cfg.viewer.lookat = (0.0, 0.0, 0.0)
# create isaac-env instance # 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 # wrap for video recording
video_kwargs = { video_kwargs = {
"video_folder": "videos", "video_folder": "videos",
......
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.9.19" version = "0.9.20"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog 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) 0.9.19 (2023-10-25)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
...@@ -173,6 +187,8 @@ Fixed ...@@ -173,6 +187,8 @@ Fixed
* Fixed the boundedness of class objects that register callbacks into the simulator. * Fixed the boundedness of class objects that register callbacks into the simulator.
These include devices, :class:`AssetBase`, :class:`SensorBase` and :class:`CommandGenerator`. These include devices, :class:`AssetBase`, :class:`SensorBase` and :class:`CommandGenerator`.
The fix ensures that object gets deleted when the user deletes the object. The fix ensures that object gets deleted when the user deletes the object.
0.9.7 (2023-09-26) 0.9.7 (2023-09-26)
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
......
...@@ -31,18 +31,24 @@ The following details the behavior of the class based on the environment variabl ...@@ -31,18 +31,24 @@ The following details the behavior of the class based on the environment variabl
* ``LIVESTREAM=3`` enables streaming via the `WebRTC Livestream`_ extension. This allows users to * ``LIVESTREAM=3`` enables streaming via the `WebRTC Livestream`_ extension. This allows users to
connect in a browser using the WebRTC protocol. connect in a browser using the WebRTC protocol.
* **Viewport**: If the environment variable ``VIEWPORT_ENABLED`` is set to non-zero, then the following
behavior happens:
* ``VIEWPORT_ENABLED=1``: Ensures that the VIEWPORT member is set to true, to enable lightweight streaming
when the full GUI is not needed (i.e. headless mode).
* **Loading ROS Bridge**: If the environment variable ``ROS_ENABLED`` is set to non-zero, then the * **Loading ROS Bridge**: If the environment variable ``ROS_ENABLED`` is set to non-zero, then the
following behavior happens: following behavior happens:
* ``ROS_ENABLED=1``: Enables the ROS1 Noetic bridge in Isaac Sim. * ``ROS_ENABLED=1``: Enables the ROS1 Noetic bridge in Isaac Sim.
* ``ROS_ENABLED=2``: Enables the ROS2 Foxy bridge in Isaac Sim. * ``ROS_ENABLED=2``: Enables the ROS2 Foxy bridge in Isaac Sim.
* **Offscreen Render**: If the environment variable ``OFFSCREEN_RENDER`` is set to 1, then the
offscreen-render pipeline is enabled. This is useful for running the simulator without a GUI but
still rendering the viewport and camera images.
* ``OFFSCREEN_RENDER=1``: Enables the offscreen-render pipeline which allows users to render
the scene without launching a GUI.
.. note::
The off-screen rendering pipeline only works when used in conjunction with the
:class:`omni.isaac.orbit.sim.SimulationContext` class. This is because the off-screen rendering
pipeline enables flags that are internally used by the SimulationContext class.
.. caution:: .. caution::
Currently, in Isaac Sim 2022.2.1, loading ``omni.isaac.ros_bridge`` before ``omni.kit.livestream.native`` Currently, in Isaac Sim 2022.2.1, loading ``omni.isaac.ros_bridge`` before ``omni.kit.livestream.native``
causes a segfault. Thus, to work around this issue, we enable the ROS-bridge extensions after the causes a segfault. Thus, to work around this issue, we enable the ROS-bridge extensions after the
...@@ -56,8 +62,8 @@ To set the environment variables, one can use the following command in the termi ...@@ -56,8 +62,8 @@ To set the environment variables, one can use the following command in the termi
.. code:: bash .. code:: bash
export LIVESTREAM=3 export REMOTE_DEPLOYMENT=3
export VIEWPORT_ENABLED=1 export OFFSCREEN_RENDER=1
# run the python script # run the python script
./orbit.sh -p source/standalone/demo/play_quadrupeds.py ./orbit.sh -p source/standalone/demo/play_quadrupeds.py
...@@ -65,7 +71,7 @@ Alternatively, one can set the environment variables to the python script direct ...@@ -65,7 +71,7 @@ Alternatively, one can set the environment variables to the python script direct
.. code:: bash .. code:: bash
LIVESTREAM=3 VIEWPORT_ENABLED=1 ./orbit.sh -p source/standalone/demo/play_quadrupeds.py REMOTE_DEPLOYMENT=3 OFFSCREEN_RENDER=1 ./orbit.sh -p source/standalone/demo/play_quadrupeds.py
.. _SimulationApp: https://docs.omniverse.nvidia.com/py/isaacsim/source/extensions/omni.isaac.kit/docs/index.html .. _SimulationApp: https://docs.omniverse.nvidia.com/py/isaacsim/source/extensions/omni.isaac.kit/docs/index.html
...@@ -82,7 +88,7 @@ import faulthandler ...@@ -82,7 +88,7 @@ import faulthandler
import os import os
import re import re
import sys import sys
from typing import ClassVar from typing import Any
from typing_extensions import Literal from typing_extensions import Literal
from omni.isaac.kit import SimulationApp from omni.isaac.kit import SimulationApp
...@@ -101,9 +107,9 @@ class AppLauncher: ...@@ -101,9 +107,9 @@ class AppLauncher:
.. note:: .. note::
Explicitly defined arguments are only given priority when their value is set to something outside Explicitly defined arguments are only given priority when their value is set to something outside
their default configuration. For example, the ``livestream`` argument is 0 by default. It only their default configuration. For example, the ``livestream`` argument is -1 by default. It only
overrides the ``LIVESTREAM`` environment variable when ``livestream`` argument is set to a non-zero overrides the ``LIVESTREAM`` environment variable when ``livestream`` argument is set to a
value. In other words, if ``livestream=0``, then the value from the environment variable value >-1. In other words, if ``livestream=-1``, then the value from the environment variable
``LIVESTREAM`` is used. ``LIVESTREAM`` is used.
Usage: Usage:
...@@ -137,38 +143,6 @@ class AppLauncher: ...@@ -137,38 +143,6 @@ class AppLauncher:
simulation_app = app_launcher.app simulation_app = app_launcher.app
""" """
RENDER: ClassVar[bool]
"""
Whether or not to render the GUI associated with IsaacSim.
This flag can be used in subsequent execution of the created simulator, i.e.
.. code:: python
from omni.isaac.core.simulation_context import SimulationContext
SimulationContext.instance().step(render=AppLauncher.RENDER)
Also, can be passed to :class:`IsaacEnv` instance using the :attr:`render` attribute, i.e.
.. code:: python
gym.make(render=app_launcher.RENDER, viewport=app_launcher.VIEWPORT)
"""
VIEWPORT: ClassVar[bool]
"""
Whether or not to render the lighter 'viewport' elements even when the application might be
executing in headless (no-GUI) mode. This is useful for off-screen rendering to gather images and
video more efficiently.
Also, can be passed to :class:`IsaacEnv` instance using the :attr:`viewport` attribute, i.e.
.. code:: python
gym.make(render=app_launcher.RENDER, viewport=app_launcher.VIEWPORT)
"""
def __init__(self, launcher_args: argparse.Namespace | dict = None, **kwargs): def __init__(self, launcher_args: argparse.Namespace | dict = None, **kwargs):
"""Create a `SimulationApp`_ instance based on the input settings. """Create a `SimulationApp`_ instance based on the input settings.
...@@ -204,7 +178,7 @@ class AppLauncher: ...@@ -204,7 +178,7 @@ class AppLauncher:
# as a kwarg, but this would require them to pass livestream, headless, ros, and # as a kwarg, but this would require them to pass livestream, headless, ros, and
# any other options we choose to add here explicitly, and with the correct keywords. # any other options we choose to add here explicitly, and with the correct keywords.
# #
# @hunter: I feel that this is cumbersone and could introduce error, and would prefer to do # @hunter: I feel that this is cumbersome and could introduce error, and would prefer to do
# some sanity checking in the add_app_launcher_args function # some sanity checking in the add_app_launcher_args function
if launcher_args is None: if launcher_args is None:
launcher_args = {} launcher_args = {}
...@@ -226,7 +200,7 @@ class AppLauncher: ...@@ -226,7 +200,7 @@ class AppLauncher:
self._headless: bool # 0: GUI, 1: Headless self._headless: bool # 0: GUI, 1: Headless
self._livestream: Literal[0, 1, 2, 3] # 0: Disabled, 1: Native, 2: Websocket, 3: WebRTC self._livestream: Literal[0, 1, 2, 3] # 0: Disabled, 1: Native, 2: Websocket, 3: WebRTC
self._ros: Literal[0, 1, 2] # 0: Disabled, 1: ROS1, 2: ROS2 self._ros: Literal[0, 1, 2] # 0: Disabled, 1: ROS1, 2: ROS2
self._viewport: bool # 0: Disabled, 1: Enabled self._offscreen_render: bool # 0: Disabled, 1: Enabled
# Integrate env-vars and input keyword args into simulation app config # Integrate env-vars and input keyword args into simulation app config
self._config_resolution(launcher_args) self._config_resolution(launcher_args)
...@@ -234,8 +208,6 @@ class AppLauncher: ...@@ -234,8 +208,6 @@ class AppLauncher:
self._create_app() self._create_app()
# Load IsaacSim extensions # Load IsaacSim extensions
self._load_extensions() self._load_extensions()
# Update global variables
self._update_globals()
""" """
Properties. Properties.
...@@ -273,6 +245,9 @@ class AppLauncher: ...@@ -273,6 +245,9 @@ class AppLauncher:
* ``ros`` (int): If one of {0, 1, 2}, then the corresponding ROS bridge is enabled. The values * ``ros`` (int): If one of {0, 1, 2}, then the corresponding ROS bridge is enabled. The values
map the same as that for the ``ROS_ENABLED`` environment variable. If :obj:`-1`, then ROS bridge is map the same as that for the ``ROS_ENABLED`` environment variable. If :obj:`-1`, then ROS bridge is
determined by the ``ROS_ENABLED`` environment variable. determined by the ``ROS_ENABLED`` environment variable.
* ``offscreen_render`` (bool): If True, the app will be launched in offscreen-render mode. The values
map the same as that for the ``OFFSCREEN_RENDER`` environment variable. If False, then offscreen-render
mode is determined by the ``OFFSCREEN_RENDER`` environment variable.
Args: Args:
parser: An argument parser instance to be extended with the AppLauncher specific options. parser: An argument parser instance to be extended with the AppLauncher specific options.
...@@ -310,21 +285,32 @@ class AppLauncher: ...@@ -310,21 +285,32 @@ class AppLauncher:
# Add custom arguments to the parser # Add custom arguments to the parser
arg_group = parser.add_argument_group("app_launcher arguments") arg_group = parser.add_argument_group("app_launcher arguments")
arg_group.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") arg_group.add_argument(
"--headless",
action="store_true",
default=AppLauncher._APPLAUNCHER_CFG_INFO["headless"][1],
help="Force display off at all times.",
)
arg_group.add_argument( arg_group.add_argument(
"--livestream", "--livestream",
type=int, type=int,
default=-1, default=AppLauncher._APPLAUNCHER_CFG_INFO["livestream"][1],
choices={-1, 0, 1, 2, 3}, choices={-1, 0, 1, 2, 3},
help="Force enable livestreaming. Mapping corresponds to that for the `LIVESTREAM` environment variable.", help="Force enable livestreaming. Mapping corresponds to that for the `LIVESTREAM` environment variable.",
) )
arg_group.add_argument( arg_group.add_argument(
"--ros", "--ros",
type=int, type=int,
default=-1, default=AppLauncher._APPLAUNCHER_CFG_INFO["ros"][1],
choices={-1, 0, 1, 2}, choices={-1, 0, 1, 2},
help="Enable ROS middleware. Mapping corresponds to that for the `ROS_ENABLED` environment variable", help="Enable ROS middleware. Mapping corresponds to that for the `ROS_ENABLED` environment variable",
) )
arg_group.add_argument(
"--offscreen_render",
action="store_true",
default=AppLauncher._APPLAUNCHER_CFG_INFO["offscreen_render"][1],
help="Enable offscreen rendering when running without a GUI.",
)
# Corresponding to the beginning of the function, # Corresponding to the beginning of the function,
# if we have removed -h/--help handling, we add it back. # if we have removed -h/--help handling, we add it back.
...@@ -336,21 +322,24 @@ class AppLauncher: ...@@ -336,21 +322,24 @@ class AppLauncher:
Internal functions. Internal functions.
""" """
_APPLAUNCHER_CONFIG_TYPES: dict[str, list[type]] = { _APPLAUNCHER_CFG_INFO: dict[str, tuple[list[type], Any]] = {
"headless": [bool], "headless": ([bool], False),
"livestream": [int], "livestream": ([int], -1),
"ros": [int], "ros": ([int], -1),
"offscreen_render": ([bool], False),
} }
"""A dictionary of arguments added manually by the :meth:`AppLauncher.add_app_launcher_args` method. """A dictionary of arguments added manually by the :meth:`AppLauncher.add_app_launcher_args` method.
These are required to be passed to AppLauncher at initialization. They have corresponding environment The values are a tuple of the expected type and default value. This is used to check against name collisions
variables as detailed in the documentation. for arguments passed to the :class:`AppLauncher` class as well as for type checking.
They have corresponding environment variables as detailed in the documentation.
""" """
# TODO: Find some internally managed NVIDIA list of these types. # TODO: Find some internally managed NVIDIA list of these types.
# SimulationApp.DEFAULT_LAUNCHER_CONFIG almost works, except that # SimulationApp.DEFAULT_LAUNCHER_CONFIG almost works, except that
# it is ambiguous where the default types are None # it is ambiguous where the default types are None
_SIMULATIONAPP_CONFIG_TYPES: dict[str, list[type]] = { _SIMULATIONAPP_CFG_TYPES: dict[str, list[type]] = {
"headless": [bool], "headless": [bool],
"active_gpu": [int, type(None)], "active_gpu": [int, type(None)],
"physics_gpu": [int], "physics_gpu": [int],
...@@ -399,10 +388,10 @@ class AppLauncher: ...@@ -399,10 +388,10 @@ class AppLauncher:
ValueError: If a key is an already existing field in the configuration parameters but ValueError: If a key is an already existing field in the configuration parameters but
should be added by calling the :meth:`AppLauncher.add_app_launcher_args. should be added by calling the :meth:`AppLauncher.add_app_launcher_args.
ValueError: If keys corresponding to those used to initialize SimulationApp ValueError: If keys corresponding to those used to initialize SimulationApp
(as found in :attr:`_SIMULATIONAPP_CONFIG_TYPES`) are of the wrong value type. (as found in :attr:`_SIMULATIONAPP_CFG_TYPES`) are of the wrong value type.
""" """
# check that no config key conflicts with AppLauncher config names # check that no config key conflicts with AppLauncher config names
applauncher_keys = set(AppLauncher._APPLAUNCHER_CONFIG_TYPES.keys()) applauncher_keys = set(AppLauncher._APPLAUNCHER_CFG_INFO.keys())
for key, value in config.items(): for key, value in config.items():
if key in applauncher_keys: if key in applauncher_keys:
raise ValueError( raise ValueError(
...@@ -411,11 +400,11 @@ class AppLauncher: ...@@ -411,11 +400,11 @@ class AppLauncher:
" argument or rename it to a non-conflicting name." " argument or rename it to a non-conflicting name."
) )
# check that type of the passed keys are valid # check that type of the passed keys are valid
simulationapp_keys = set(AppLauncher._SIMULATIONAPP_CONFIG_TYPES.keys()) simulationapp_keys = set(AppLauncher._SIMULATIONAPP_CFG_TYPES.keys())
for key, value in config.items(): for key, value in config.items():
if key in simulationapp_keys: if key in simulationapp_keys:
given_type = type(value) given_type = type(value)
expected_types = AppLauncher._SIMULATIONAPP_CONFIG_TYPES[key] expected_types = AppLauncher._SIMULATIONAPP_CFG_TYPES[key]
if type(value) not in set(expected_types): if type(value) not in set(expected_types):
raise ValueError( raise ValueError(
f"Invalid value type for the argument '{key}': {given_type}. Expected one of {expected_types}," f"Invalid value type for the argument '{key}': {given_type}. Expected one of {expected_types},"
...@@ -436,7 +425,7 @@ class AppLauncher: ...@@ -436,7 +425,7 @@ class AppLauncher:
# --LIVESTREAM logic-- # --LIVESTREAM logic--
# #
livestream_env = int(os.environ.get("LIVESTREAM", 0)) livestream_env = int(os.environ.get("LIVESTREAM", 0))
livestream_arg = launcher_args.pop("livestream", -1) livestream_arg = launcher_args.pop("livestream", AppLauncher._APPLAUNCHER_CFG_INFO["livestream"][1])
livestream_valid_vals = {0, 1, 2, 3} livestream_valid_vals = {0, 1, 2, 3}
# Value checking on LIVESTREAM # Value checking on LIVESTREAM
if livestream_env not in livestream_valid_vals: if livestream_env not in livestream_valid_vals:
...@@ -467,7 +456,7 @@ class AppLauncher: ...@@ -467,7 +456,7 @@ class AppLauncher:
# HEADLESS is initially passed as an int instead of # HEADLESS is initially passed as an int instead of
# the bool of headless_arg to avoid messy string processing, # the bool of headless_arg to avoid messy string processing,
headless_env = int(os.environ.get("HEADLESS", 0)) headless_env = int(os.environ.get("HEADLESS", 0))
headless_arg = launcher_args.pop("headless", False) headless_arg = launcher_args.pop("headless", AppLauncher._APPLAUNCHER_CFG_INFO["headless"][1])
headless_valid_vals = {0, 1} headless_valid_vals = {0, 1}
# Value checking on HEADLESS # Value checking on HEADLESS
if headless_env not in headless_valid_vals: if headless_env not in headless_valid_vals:
...@@ -501,7 +490,7 @@ class AppLauncher: ...@@ -501,7 +490,7 @@ class AppLauncher:
# --ROS logic-- # --ROS logic--
# #
ros_env = int(os.environ.get("ROS_ENABLED", 0)) ros_env = int(os.environ.get("ROS_ENABLED", 0))
ros_arg = int(launcher_args.pop("ros", -1)) ros_arg = int(launcher_args.pop("ros", AppLauncher._APPLAUNCHER_CFG_INFO["ros"][1]))
ros_valid_vals = {0, 1, 2} ros_valid_vals = {0, 1, 2}
# Value checking on LIVESTREAM # Value checking on LIVESTREAM
if ros_env not in ros_valid_vals: if ros_env not in ros_valid_vals:
...@@ -524,17 +513,24 @@ class AppLauncher: ...@@ -524,17 +513,24 @@ class AppLauncher:
else: else:
self._ros = ros_env self._ros = ros_env
# --VIEWPORT logic-- # --OFFSCREEN_RENDER logic--
# #
# off-screen rendering # off-screen rendering
viewport_env = int(os.environ.get("VIEWPORT_ENABLED", 0)) offscreen_render_env = int(os.environ.get("OFFSCREEN_RENDER", 0))
viewport_valid_vals = {0, 1} offscreen_render_arg = launcher_args.pop(
if viewport_env not in viewport_valid_vals: "offscreen_render", AppLauncher._APPLAUNCHER_CFG_INFO["offscreen_render"][1]
)
offscreen_render_valid_vals = {0, 1}
if offscreen_render_env not in offscreen_render_valid_vals:
raise ValueError( raise ValueError(
f"Invalid value for environment variable `VIEWPORT_ENABLED`: {viewport_env} ." f"Invalid value for environment variable `OFFSCREEN_RENDER`: {offscreen_render_env} ."
f"Expected: {viewport_valid_vals} ." f"Expected: {offscreen_render_valid_vals} ."
) )
self._viewport = bool(viewport_env) # We allow offscreen_render kwarg to supersede OFFSCREEN_RENDER envvar
if offscreen_render_arg is True:
self._offscreen_render = offscreen_render_arg
else:
self._offscreen_render = bool(offscreen_render_env)
# Check if input keywords contain an 'experience' file setting # Check if input keywords contain an 'experience' file setting
# Note: since experience is taken as a separate argument by Simulation App, we store it separately # Note: since experience is taken as a separate argument by Simulation App, we store it separately
...@@ -544,7 +540,7 @@ class AppLauncher: ...@@ -544,7 +540,7 @@ class AppLauncher:
# Assign all the passed settings to a dictionary for the simulation app # Assign all the passed settings to a dictionary for the simulation app
self._simulationapp_config = { self._simulationapp_config = {
key: launcher_args[key] key: launcher_args[key]
for key in set(AppLauncher._SIMULATIONAPP_CONFIG_TYPES.keys()) & set(launcher_args.keys()) for key in set(AppLauncher._SIMULATIONAPP_CFG_TYPES.keys()) & set(launcher_args.keys())
} }
def _create_app(self): def _create_app(self):
...@@ -613,10 +609,15 @@ class AppLauncher: ...@@ -613,10 +609,15 @@ class AppLauncher:
else: else:
raise ValueError(f"Invalid value for ros: {self._ros}. Expected: 1, 2 .") raise ValueError(f"Invalid value for ros: {self._ros}. Expected: 1, 2 .")
# set carb setting to indicate orbit's offscreen_render pipeline should be enabled
# this flag is used by the SimulationContext class to enable the offscreen_render pipeline
# when the render() method is called.
carb_settings_iface.set_bool("/orbit/offscreen_render/enabled", self._offscreen_render)
# enable extensions for off-screen rendering # enable extensions for off-screen rendering
# note: depending on the app file, some extensions might not be available in it. # note: depending on the app file, some extensions might not be available in it.
# Thus, we manually enable these extensions to make sure they are available. # Thus, we manually enable these extensions to make sure they are available.
if self._viewport != 0 or not self._headless: if self._offscreen_render or not self._headless:
# note: enabling extensions is order-sensitive. please do not change the order! # note: enabling extensions is order-sensitive. please do not change the order!
# extension to enable UI buttons (otherwise we get attribute errors) # extension to enable UI buttons (otherwise we get attribute errors)
enable_extension("omni.kit.window.toolbar") enable_extension("omni.kit.window.toolbar")
...@@ -643,12 +644,3 @@ class AppLauncher: ...@@ -643,12 +644,3 @@ class AppLauncher:
"/persistent/isaac/asset_root/nvidia", "/persistent/isaac/asset_root/nvidia",
"http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets", "http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets",
) )
def _update_globals(self):
"""Updates global variables which depend upon AppLauncher's resolved config member variables."""
# update the global flags
# TODO: Remove all these global flags. We don't need it anymore.
# -- render GUI
self.RENDER = not self._headless or self._livestream
# -- render viewport
self.VIEWPORT = self._viewport
...@@ -28,11 +28,13 @@ class ViewerCfg: ...@@ -28,11 +28,13 @@ class ViewerCfg:
"""Initial camera position (in m). Default is (7.5, 7.5, 7.5).""" """Initial camera position (in m). Default is (7.5, 7.5, 7.5)."""
lookat: Tuple[float, float, float] = (0.0, 0.0, 0.0) 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).""" """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) resolution: Tuple[int, int] = (1280, 720)
"""The resolution (width, height) of the default viewport (in pixels). Default is (1280, 720). """The resolution (width, height) of the camera specified using :attr:`cam_prim_path`.
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.
""" """
......
...@@ -110,10 +110,10 @@ class RLEnv(BaseEnv, gym.Env): ...@@ -110,10 +110,10 @@ class RLEnv(BaseEnv, gym.Env):
# extend UI elements # extend UI elements
# we need to do this here after all the managers are initialized # we need to do this here after all the managers are initialized
# this is because they dictate the sensors and commands right now # 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() self._build_ui()
else: 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 = None
self._orbit_window_elements = dict() self._orbit_window_elements = dict()
...@@ -222,6 +222,10 @@ class RLEnv(BaseEnv, gym.Env): ...@@ -222,6 +222,10 @@ class RLEnv(BaseEnv, gym.Env):
self.sim.step(render=False) self.sim.step(render=False)
# update buffers at sim dt # update buffers at sim dt
self.scene.update(dt=self.physics_dt) self.scene.update(dt=self.physics_dt)
# perform rendering if gui is enabled
if self.sim.has_gui():
self.sim.render()
# post-step: # post-step:
# -- update env counters (used for curriculum generation) # -- update env counters (used for curriculum generation)
self.episode_length_buf += 1 # step in current episode (per env) self.episode_length_buf += 1 # step in current episode (per env)
...@@ -257,11 +261,12 @@ class RLEnv(BaseEnv, gym.Env): ...@@ -257,11 +261,12 @@ class RLEnv(BaseEnv, gym.Env):
mode: The mode to render with. Defaults to "human". mode: The mode to render with. Defaults to "human".
Returns: Returns:
The rendered image as a numpy array if mode is "rgb_array" and offscreen The rendered image as a numpy array if mode is "rgb_array".
rendering is enabled.
Raises: 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. NotImplementedError: If an unsupported rendering mode is specified.
""" """
# run a rendering step of the simulator # run a rendering step of the simulator
...@@ -270,28 +275,34 @@ class RLEnv(BaseEnv, gym.Env): ...@@ -270,28 +275,34 @@ class RLEnv(BaseEnv, gym.Env):
if mode == "human": if mode == "human":
return None return None
elif mode == "rgb_array": elif mode == "rgb_array":
# 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) return np.zeros((self.cfg.viewer.resolution[1], self.cfg.viewer.resolution[0], 3), dtype=np.uint8)
# TODO: Add support to allow video recording!! else:
# # check if viewport is enabled -- if not, then complain because we won't get any data return rgb_data[:, :, :3]
# 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]
else: else:
raise NotImplementedError( raise NotImplementedError(
f"Render mode '{mode}' is not supported. Please use: {self.metadata['render.modes']}." f"Render mode '{mode}' is not supported. Please use: {self.metadata['render.modes']}."
......
...@@ -72,27 +72,28 @@ class SimulationContext(_SimulationContext): ...@@ -72,27 +72,28 @@ class SimulationContext(_SimulationContext):
Render modes correspond to how the viewport and other UI elements (such as listeners to keyboard or mouse Render modes correspond to how the viewport and other UI elements (such as listeners to keyboard or mouse
events) are updated. There are three main components that can be updated when the simulation is rendered: events) are updated. There are three main components that can be updated when the simulation is rendered:
1. **`Viewports`_**: These are windows where you can see the rendered scene. 1. **UI elements and other extensions**: These are UI elements (such as buttons, sliders, etc.) and other
extensions that are running in the background that need to be updated when the simulation is running.
2. **Cameras**: These are typically based on Hydra textures and are used to render the scene from different 2. **Cameras**: These are typically based on Hydra textures and are used to render the scene from different
viewpoints. They can be attached to a viewport or be used independently to render the scene. viewpoints. They can be attached to a viewport or be used independently to render the scene.
3. **UI elements and other extensions**: These are UI elements (such as buttons, sliders, etc.) and other 3. **`Viewports`_**: These are windows where you can see the rendered scene.
extensions that are running in the background that need to be updated when the simulation is running.
Updating each of the above components has a different overhead. For example, updating the viewports is Updating each of the above components has a different overhead. For example, updating the viewports is
computationally expensive compared to updating the UI elements. Therefore, it is useful to be able to computationally expensive compared to updating the UI elements. Therefore, it is useful to be able to
control what is updated when the simulation is rendered. This is where the render mode comes in. There are control what is updated when the simulation is rendered. This is where the render mode comes in. There are
four different render modes: four different render modes:
* :attr:`HEADLESS`: Headless mode, where the simulation is running without a GUI. * :attr:`NO_GUI_OR_RENDERING`: The simulation is running without a GUI and off-screen rendering flag is disabled,
so none of the above are updated.
* :attr:`NO_RENDERING`: No rendering, where only 1 is updated at a lower rate.
* :attr:`PARTIAL_RENDERING`: Partial rendering, where only 1 and 2 are updated.
* :attr:`FULL_RENDERING`: Full rendering, where everything (1, 2, 3) is updated. * :attr:`FULL_RENDERING`: Full rendering, where everything (1, 2, 3) is updated.
* :attr:`PARTIAL_RENDERING`: Partial rendering, where only 2 and 3 are updated.
* :attr:`NO_RENDERING`: No rendering, where only 3 is updated at a lower rate.
.. _Viewports: https://docs.omniverse.nvidia.com/extensions/latest/ext_viewport.html .. _Viewports: https://docs.omniverse.nvidia.com/extensions/latest/ext_viewport.html
""" """
HEADLESS = -1 NO_GUI_OR_RENDERING = -1
"""Headless mode, where the simulation is running without a GUI.""" """The simulation is running without a GUI and off-screen rendering is disabled."""
NO_RENDERING = 0 NO_RENDERING = 0
"""No rendering, where only other UI elements are updated at a lower rate.""" """No rendering, where only other UI elements are updated at a lower rate."""
PARTIAL_RENDERING = 1 PARTIAL_RENDERING = 1
...@@ -133,13 +134,30 @@ class SimulationContext(_SimulationContext): ...@@ -133,13 +134,30 @@ class SimulationContext(_SimulationContext):
# reference: https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/Geometry.html?highlight=capsule#geometry # reference: https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/Geometry.html?highlight=capsule#geometry
carb_settings_iface.set_bool("/physics/collisionConeCustomGeometry", False) carb_settings_iface.set_bool("/physics/collisionConeCustomGeometry", False)
carb_settings_iface.set_bool("/physics/collisionCylinderCustomGeometry", False) carb_settings_iface.set_bool("/physics/collisionCylinderCustomGeometry", False)
# read flag for whether headless mode is enabled
# note: we read this once since it is not expected to change during runtime # note: we read this once since it is not expected to change during runtime
self._is_headless = not carb_settings_iface.get("/app/window/enabled") # read flag for whether a local GUI is enabled
self._local_gui = carb_settings_iface.get("/app/window/enabled")
# read flag for whether livestreaming GUI is enabled
self._livestream_gui = carb_settings_iface.get("/app/livestream/enabled")
# read flag for whether the orbit viewport capture pipeline will be used,
# casting None to False if the flag doesn't exist
# this flag is set from the AppLauncher class
self._offscreen_render = bool(carb_settings_iface.get("/orbit/offscreen_render/enabled"))
# flag for whether any GUI will be rendered (local, livestreamed or viewport)
self._has_gui = self._local_gui or self._livestream_gui
# store the default render mode # store the default render mode
if self._is_headless: if not self._has_gui and not self._offscreen_render:
# set default render mode # set default render mode
self.render_mode = self.RenderMode.HEADLESS # note: this is the terminal state: cannot exit from this render mode
self.render_mode = self.RenderMode.NO_GUI_OR_RENDERING
# set viewport context to None
self._viewport_context = None
self._viewport_window = None
elif not self._has_gui and self._offscreen_render:
# set default render mode
# note: this is the terminal state: cannot exit from this render mode
self.render_mode = self.RenderMode.PARTIAL_RENDERING
# set viewport context to None # set viewport context to None
self._viewport_context = None self._viewport_context = None
self._viewport_window = None self._viewport_window = None
...@@ -149,6 +167,7 @@ class SimulationContext(_SimulationContext): ...@@ -149,6 +167,7 @@ class SimulationContext(_SimulationContext):
from omni.kit.viewport.utility import get_active_viewport from omni.kit.viewport.utility import get_active_viewport
# set default render mode # set default render mode
# note: this can be changed by calling the `set_render_mode` function
self.render_mode = self.RenderMode.FULL_RENDERING self.render_mode = self.RenderMode.FULL_RENDERING
# acquire viewport context # acquire viewport context
self._viewport_context = get_active_viewport() self._viewport_context = get_active_viewport()
...@@ -163,7 +182,7 @@ class SimulationContext(_SimulationContext): ...@@ -163,7 +182,7 @@ class SimulationContext(_SimulationContext):
# override enable scene querying if rendering is enabled # override enable scene querying if rendering is enabled
# this is needed for some GUI features # this is needed for some GUI features
if not self._is_headless: if self._has_gui:
self.cfg.enable_scene_query_support = True self.cfg.enable_scene_query_support = True
# set up flatcache/fabric interface (default is None) # set up flatcache/fabric interface (default is None)
# this is needed to flush the flatcache data into Hydra manually when calling `render()` # this is needed to flush the flatcache data into Hydra manually when calling `render()`
...@@ -195,13 +214,12 @@ class SimulationContext(_SimulationContext): ...@@ -195,13 +214,12 @@ class SimulationContext(_SimulationContext):
Operations - New. Operations - New.
""" """
def is_headless(self) -> bool: def has_gui(self) -> bool:
"""Returns whether the simulation is running in headless mode. """Returns whether the simulation has a GUI enabled.
Note: The simulation has a GUI enabled either locally or livestreamed.
Headless mode is enabled when the simulator is running without a GUI.
""" """
return self._is_headless return self._has_gui
def get_version(self) -> tuple[int, int, int]: def get_version(self) -> tuple[int, int, int]:
"""Returns the version of the simulator. """Returns the version of the simulator.
...@@ -246,17 +264,26 @@ class SimulationContext(_SimulationContext): ...@@ -246,17 +264,26 @@ class SimulationContext(_SimulationContext):
Please see :class:`RenderMode` for more information on the different render modes. Please see :class:`RenderMode` for more information on the different render modes.
.. note:: .. note::
When running in headless mode, we do not need to choose whether the viewport needs to render or not (since When no GUI is available (locally or livestreamed), we do not need to choose whether the viewport
there is no GUI). Thus, in this case, calling the function will not change the render mode. needs to render or not (since there is no GUI). Thus, in this case, calling the function will not
change the render mode.
Args: Args:
mode: The rendering mode. Defaults to None, in which case the mode (RenderMode): The rendering mode. If different than SimulationContext's rendering mode,
current rendering mode is used. SimulationContext's mode is changed to the new mode.
Raises:
ValueError: If the input mode is not supported.
""" """
# check if mode change is possible -- not possible when no GUI is available
if not self._has_gui:
carb.log_warn(
f"Cannot change render mode when GUI is disabled. Using the default render mode: {self.render_mode}."
)
return
# check if there is a mode change # check if there is a mode change
# note: this is mostly needed for GUI when we want to switch between full rendering and no rendering. # note: this is mostly needed for GUI when we want to switch between full rendering and no rendering.
# for headless mode, we don't need to do anything. if mode != self.render_mode:
if mode != self.render_mode and self.render_mode != self.RenderMode.HEADLESS:
if mode == self.RenderMode.FULL_RENDERING: if mode == self.RenderMode.FULL_RENDERING:
# display the viewport and enable updates # display the viewport and enable updates
self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess] self._viewport_context.updates_enabled = True # pyright: ignore [reportOptionalMemberAccess]
...@@ -265,10 +292,6 @@ class SimulationContext(_SimulationContext): ...@@ -265,10 +292,6 @@ class SimulationContext(_SimulationContext):
# hide the viewport and disable updates # hide the viewport and disable updates
self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess] self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess]
self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess] self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess]
elif mode == self.RenderMode.NO_RENDERING:
# hide the viewport and disable updates
self._viewport_context.updates_enabled = False # pyright: ignore [reportOptionalMemberAccess]
self._viewport_window.visible = False # pyright: ignore [reportOptionalMemberAccess]
# reset the throttle counter # reset the throttle counter
self._render_throttle_counter = 0 self._render_throttle_counter = 0
else: else:
...@@ -333,7 +356,6 @@ class SimulationContext(_SimulationContext): ...@@ -333,7 +356,6 @@ class SimulationContext(_SimulationContext):
Args: Args:
render: Whether to render the scene after stepping the physics simulation. render: Whether to render the scene after stepping the physics simulation.
If set to False, the scene is not rendered and only the physics simulation is stepped. If set to False, the scene is not rendered and only the physics simulation is stepped.
Defaults to True.
""" """
# check if the simulation timeline is paused. in that case keep stepping until it is playing # check if the simulation timeline is paused. in that case keep stepping until it is playing
if not self.is_playing(): if not self.is_playing():
...@@ -348,6 +370,7 @@ class SimulationContext(_SimulationContext): ...@@ -348,6 +370,7 @@ class SimulationContext(_SimulationContext):
# without this the app becomes unresponsive. # without this the app becomes unresponsive.
# FIXME: This steps physics as well, which we is not good in general. # FIXME: This steps physics as well, which we is not good in general.
self.app.update() self.app.update()
# step the simulation # step the simulation
super().step(render=render) super().step(render=render)
...@@ -360,31 +383,24 @@ class SimulationContext(_SimulationContext): ...@@ -360,31 +383,24 @@ class SimulationContext(_SimulationContext):
Please see :class:`RenderMode` for more information on the different render modes. Please see :class:`RenderMode` for more information on the different render modes.
.. note::
When running in headless mode, we do not need to choose whether the viewport needs to render or not (since
there is no GUI). Thus, in this case, calling the function always render the viewport and
it is not possible to change the render mode.
Args: Args:
mode: The rendering mode. Defaults to None, in which case the mode: The rendering mode. Defaults to None, in which case the current rendering mode is used.
current rendering mode is used.
""" """
# check if we need to change the render mode # check if we need to change the render mode
if mode is not None: if mode is not None:
self.set_render_mode(mode) self.set_render_mode(mode)
# render based on the render mode # render based on the render mode
# -- no rendering: throttle the rendering frequency to keep the UI responsive if self.render_mode == self.RenderMode.NO_GUI_OR_RENDERING:
if self.render_mode == self.RenderMode.NO_RENDERING: # we never want to render anything here (this is for complete headless mode)
pass
elif self.render_mode == self.RenderMode.NO_RENDERING:
# throttle the rendering frequency to keep the UI responsive
self._render_throttle_counter += 1 self._render_throttle_counter += 1
if self._render_throttle_counter % self._render_throttle_period == 0: if self._render_throttle_counter % self._render_throttle_period == 0:
self._render_throttle_counter = 0 self._render_throttle_counter = 0
# here we don't render viewport so don't need to flush flatcache # here we don't render viewport so don't need to flush flatcache
super().render() super().render()
elif self.render_mode == self.RenderMode.HEADLESS:
# we never want to render anything here -- camera rendering will also not work then?
pass
else: else:
# this is called even if we are in headless mode - we allow this for off-screen rendering
# manually flush the flatcache data to update Hydra textures # manually flush the flatcache data to update Hydra textures
if self._fabric_iface is not None: if self._fabric_iface is not None:
self._fabric_iface.update(0.0, 0.0) self._fabric_iface.update(0.0, 0.0)
...@@ -515,6 +531,7 @@ class SimulationContext(_SimulationContext): ...@@ -515,6 +531,7 @@ class SimulationContext(_SimulationContext):
rep_status = rep.orchestrator.get_status() rep_status = rep.orchestrator.get_status()
if rep_status not in [rep.orchestrator.Status.STOPPED, rep.orchestrator.Status.STOPPING]: if rep_status not in [rep.orchestrator.Status.STOPPED, rep.orchestrator.Status.STOPPING]:
rep.orchestrator.stop() rep.orchestrator.stop()
if rep_status != rep.orchestrator.Status.STOPPED:
rep.orchestrator.wait_until_complete() rep.orchestrator.wait_until_complete()
except Exception: except Exception:
pass pass
......
...@@ -118,7 +118,7 @@ def main(): ...@@ -118,7 +118,7 @@ def main():
break break
# If simulation is paused, then skip. # If simulation is paused, then skip.
if not sim.is_playing(): if not sim.is_playing():
sim.step(render=app_launcher.RENDER) sim.step()
continue continue
# reset # reset
if count % 50 == 0: if count % 50 == 0:
...@@ -149,7 +149,7 @@ def main(): ...@@ -149,7 +149,7 @@ def main():
# write data to sim # write data to sim
scene.write_data_to_sim() scene.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# read data from sim # read data from sim
scene.update(sim_dt) scene.update(sim_dt)
# update sim-time # update sim-time
......
...@@ -95,7 +95,7 @@ class TestSimulationContext(unittest.TestCase): ...@@ -95,7 +95,7 @@ class TestSimulationContext(unittest.TestCase):
sim = SimulationContext() sim = SimulationContext()
# check default render mode # 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): def test_boundedness(self):
"""Test that the boundedness of the simulation context remains constant. """Test that the boundedness of the simulation context remains constant.
......
...@@ -113,8 +113,6 @@ class RslRlVecEnvWrapper(gym.Wrapper): ...@@ -113,8 +113,6 @@ class RslRlVecEnvWrapper(gym.Wrapper):
def step(self, actions: torch.Tensor) -> VecEnvStepReturn: # noqa: D102 def step(self, actions: torch.Tensor) -> VecEnvStepReturn: # noqa: D102
# record step information # record step information
obs_dict, rew, dones, extras = self.env.step(actions) obs_dict, rew, dones, extras = self.env.step(actions)
# render the environment to allow for visualization
self.env.render()
# return step information # return step information
obs = obs_dict["policy"] obs = obs_dict["policy"]
extras["observations"] = obs_dict extras["observations"] = obs_dict
......
...@@ -133,7 +133,7 @@ def main(): ...@@ -133,7 +133,7 @@ def main():
robot.set_joint_position_target(actions) robot.set_joint_position_target(actions)
robot.write_data_to_sim() robot.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# update buffers # update buffers
robot.update(sim_dt) robot.update(sim_dt)
# update sim-time # update sim-time
......
...@@ -159,7 +159,7 @@ def main(): ...@@ -159,7 +159,7 @@ def main():
# Simulate physics # Simulate physics
while simulation_app.is_running(): while simulation_app.is_running():
# Step simulation # Step simulation
sim.step(render=app_launcher.RENDER) sim.step()
# Update camera data # Update camera data
camera.update(dt=0.0) camera.update(dt=0.0)
......
...@@ -142,7 +142,7 @@ def main(): ...@@ -142,7 +142,7 @@ def main():
robot.set_joint_position_target(actions) robot.set_joint_position_target(actions)
robot.write_data_to_sim() robot.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
ep_step_count += 1 ep_step_count += 1
......
...@@ -188,7 +188,7 @@ def main(): ...@@ -188,7 +188,7 @@ def main():
robot.set_joint_position_target(joint_pos_des, arm_joint_ids) robot.set_joint_position_target(joint_pos_des, arm_joint_ids)
robot.write_data_to_sim() robot.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
count += 1 count += 1
......
...@@ -115,7 +115,7 @@ def main(): ...@@ -115,7 +115,7 @@ def main():
robot.set_joint_position_target(robot.data.default_joint_pos.clone()) robot.set_joint_position_target(robot.data.default_joint_pos.clone())
robot.write_data_to_sim() robot.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
count += 1 count += 1
......
...@@ -158,7 +158,7 @@ def main(): ...@@ -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.set_joint_position_target(actions[:, 3:], joint_ids=[3, 4, 5, 6, 7, 8, 9, 10, 11])
robot.write_data_to_sim() robot.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
ep_step_count += 1 ep_step_count += 1
......
...@@ -173,7 +173,7 @@ def main(): ...@@ -173,7 +173,7 @@ def main():
break break
# If simulation is paused, then skip. # If simulation is paused, then skip.
if not sim.is_playing(): if not sim.is_playing():
sim.step(render=app_launcher.RENDER) sim.step()
continue continue
# reset # reset
if count % 350 == 0: if count % 350 == 0:
...@@ -193,7 +193,7 @@ def main(): ...@@ -193,7 +193,7 @@ def main():
# step simulation # step simulation
# FIXME: this is needed for lula to update the buffers! # FIXME: this is needed for lula to update the buffers!
# the bug has been reported to the lula team # the bug has been reported to the lula team
sim.step(render=app_launcher.RENDER) sim.step()
# set the controller commands # set the controller commands
rmp_controller.set_command(rmp_commands) rmp_controller.set_command(rmp_commands)
# compute the joint commands # compute the joint commands
...@@ -225,7 +225,7 @@ def main(): ...@@ -225,7 +225,7 @@ def main():
# apply actions # apply actions
robot.apply_action(robot_actions) robot.apply_action(robot_actions)
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
count += 1 count += 1
......
...@@ -112,7 +112,7 @@ def main(): ...@@ -112,7 +112,7 @@ def main():
break break
# If simulation is paused, then skip. # If simulation is paused, then skip.
if not sim.is_playing(): if not sim.is_playing():
sim.step(render=app_launcher.RENDER) sim.step()
continue continue
# reset # reset
if count % 50 == 0: if count % 50 == 0:
...@@ -143,7 +143,7 @@ def main(): ...@@ -143,7 +143,7 @@ def main():
# write data to sim # write data to sim
scene.write_data_to_sim() scene.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# read data from sim # read data from sim
scene.update(sim_dt) scene.update(sim_dt)
# update sim-time # update sim-time
......
...@@ -112,7 +112,7 @@ def main(): ...@@ -112,7 +112,7 @@ def main():
# apply sim data # apply sim data
rigid_object.write_data_to_sim() rigid_object.write_data_to_sim()
# perform step # perform step
sim.step(render=app_launcher.RENDER) sim.step()
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
count += 1 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