Unverified Commit 3f2beaf5 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Fixes unit tests of existing features (#134)

# Description

This PR checks that all the existing scripts in the codebase work as
expected. The last few merges led to the deletion of some files that
were no longer available to import in the unit tests. Also renamed files
in the test to follow the following convention:

* `test_*.py` : A script that tests a feature using unittest fixture
* `check_*.py`: A script that runs the feature but doesn't necessarily
put them as a unittest fixture.

## 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
parent 8c5a0697
...@@ -21,7 +21,6 @@ omni.isaac.orbit extension ...@@ -21,7 +21,6 @@ omni.isaac.orbit extension
orbit.command_generators orbit.command_generators
orbit.utils orbit.utils
orbit.utils.assets orbit.utils.assets
orbit.utils.kit
orbit.utils.math orbit.utils.math
orbit.utils.mdp orbit.utils.mdp
orbit.compat orbit.compat
......
...@@ -8,7 +8,8 @@ omni.isaac.orbit.compat ...@@ -8,7 +8,8 @@ omni.isaac.orbit.compat
* :mod:`omni.isaac.orbit.markers` * :mod:`omni.isaac.orbit.markers`
* :mod:`omni.isaac.orbit.sensors` * :mod:`omni.isaac.orbit.sensors`
* :mod:`omni.isaac.orbit.utils.mdp` * :mod:`omni.isaac.orbit.managers`
* :mod:`omni.isaac.orbit.sim`
Markers Markers
------- -------
...@@ -103,3 +104,11 @@ MDP Managers ...@@ -103,3 +104,11 @@ MDP Managers
:members: :members:
:undoc-members: :undoc-members:
:show-inheritance: :show-inheritance:
Kit Utilities
-------------
.. automodule:: omni.isaac.orbit.compat.utils.kit
:members:
:undoc-members:
:show-inheritance:
omni.isaac.orbit.utils.kit
==========================
.. automodule:: omni.isaac.orbit.utils.kit
:members:
:undoc-members:
:show-inheritance:
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.9.2" version = "0.9.3"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.9.3 (2023-08-23)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Enabled the `faulthander <https://docs.python.org/3/library/faulthandler.html>`_ to catch segfaults and print
the stack trace. This is enabled by default in the :class:`omni.isaac.orbit.app.AppLauncher` class.
Fixed
^^^^^
* Re-added the :mod:`omni.isaac.orbit.utils.kit` to the ``compat`` directory and fixed all the references to it.
* Fixed the deletion of Replicator nodes for the :class:`omni.isaac.orbit.sensors.Camera` class. Earlier, the
Replicator nodes were not being deleted when the camera was deleted. However, this does not prevent the random
crashes that happen when the camera is deleted.
* Fixed the :meth:`omni.isaac.orbit.utils.math.convert_quat` to support both numpy and torch tensors.
Changed
^^^^^^^
* Renamed all the scripts inside the ``test`` directory to follow the convention:
* ``test_<module_name>.py``: Tests for the module ``<module_name>`` using unittest.
* ``check_<module_name>``: Check for the module ``<module_name>`` using python main function.
0.9.2 (2023-08-22) 0.9.2 (2023-08-22)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -72,6 +72,7 @@ Alternatively, one can set the environment variables to the python script direct ...@@ -72,6 +72,7 @@ Alternatively, one can set the environment variables to the python script direct
""" """
import faulthandler
import os import os
import re import re
import sys import sys
...@@ -135,6 +136,9 @@ class AppLauncher: ...@@ -135,6 +136,9 @@ class AppLauncher:
.. _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
.. _documentation: https://docs.omniverse.nvidia.com/py/isaacsim/source/extensions/omni.isaac.kit/docs/index.html .. _documentation: https://docs.omniverse.nvidia.com/py/isaacsim/source/extensions/omni.isaac.kit/docs/index.html
""" """
# Enable call-stack on crash
faulthandler.enable()
# Headless is always true for remote deployment # Headless is always true for remote deployment
remote_deployment = int(os.environ.get("REMOTE_DEPLOYMENT", 0)) remote_deployment = int(os.environ.get("REMOTE_DEPLOYMENT", 0))
# resolve headless execution of simulation app # resolve headless execution of simulation app
......
...@@ -15,7 +15,7 @@ from omni.isaac.core.materials import PreviewSurface ...@@ -15,7 +15,7 @@ from omni.isaac.core.materials import PreviewSurface
from omni.isaac.core.prims import GeometryPrim from omni.isaac.core.prims import GeometryPrim
from pxr import Gf, UsdGeom from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR, check_file_path from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR, check_file_path
......
...@@ -74,6 +74,7 @@ class Camera(SensorBase): ...@@ -74,6 +74,7 @@ class Camera(SensorBase):
cfg (CameraCfg): The configuration parameters. cfg (CameraCfg): The configuration parameters.
Raises: Raises:
RuntimeError: If no camera prim is found at the given path.
ValueError: If the sensor types intersect with in the unsupported list. ValueError: If the sensor types intersect with in the unsupported list.
""" """
# initialize base class # initialize base class
...@@ -89,10 +90,10 @@ class Camera(SensorBase): ...@@ -89,10 +90,10 @@ class Camera(SensorBase):
self.cfg.spawn.func( self.cfg.spawn.func(
self.cfg.prim_path, self.cfg.spawn, translation=self.cfg.offset.pos, orientation=rot_offset self.cfg.prim_path, self.cfg.spawn, translation=self.cfg.offset.pos, orientation=rot_offset
) )
# check that spawn was successful # check that spawn was successful
matching_prim_paths = prim_utils.find_matching_prim_paths(self.cfg.prim_path) matching_prim_paths = prim_utils.find_matching_prim_paths(self.cfg.prim_path)
if len(matching_prim_paths) == 0: if len(matching_prim_paths) == 0:
raise RuntimeError(f"Could not find prim with path {self.cfg.prim_path}.") raise RuntimeError(f"Could not find prim with path {self.cfg.prim_path}.")
# UsdGeom Camera prim for the sensor # UsdGeom Camera prim for the sensor
self._sensor_prims: list[UsdGeom.Camera] = list() self._sensor_prims: list[UsdGeom.Camera] = list()
...@@ -111,6 +112,15 @@ class Camera(SensorBase): ...@@ -111,6 +112,15 @@ class Camera(SensorBase):
" implementation from the omni.isaac.orbit.compat.camera module." " implementation from the omni.isaac.orbit.compat.camera module."
) )
def __del__(self):
"""Unsubscribes from callbacks and detach from the replicator registry."""
# unsubscribe callbacks
super().__del__()
# delete from replicator registry
for _, annotators in self._rep_registry.items():
for annotator, render_product_path in zip(annotators, self._render_product_paths):
annotator.detach([render_product_path])
def __str__(self) -> str: def __str__(self) -> str:
"""Returns: A string containing information about the instance.""" """Returns: A string containing information about the instance."""
# message for class # message for class
...@@ -272,7 +282,7 @@ class Camera(SensorBase): ...@@ -272,7 +282,7 @@ class Camera(SensorBase):
if orientations is not None: if orientations is not None:
if isinstance(orientations, np.ndarray): if isinstance(orientations, np.ndarray):
orientations = torch.from_numpy(orientations).to(device=self._device) orientations = torch.from_numpy(orientations).to(device=self._device)
elif not isinstance(orientations, torch.tensor): elif not isinstance(orientations, torch.Tensor):
orientations = torch.tensor(orientations, device=self._device) orientations = torch.tensor(orientations, device=self._device)
orientations = convert_orientation_convention(orientations, origin=convention, target="opengl") orientations = convert_orientation_convention(orientations, origin=convention, target="opengl")
# set the pose # set the pose
...@@ -476,8 +486,8 @@ class Camera(SensorBase): ...@@ -476,8 +486,8 @@ class Camera(SensorBase):
# -- pose of the cameras # -- pose of the cameras
self._data.pos_w = torch.zeros((self._view.count, 3), device=self._device) self._data.pos_w = torch.zeros((self._view.count, 3), device=self._device)
self._data.quat_w_ros = torch.zeros((self._view.count, 4), device=self._device) self._data.quat_w_ros = torch.zeros((self._view.count, 4), device=self._device)
self._data.quat_w_world = torch.zeros((self._view.count, 4), device=self._device) self._data.quat_w_world = torch.zeros_like(self._data.quat_w_ros)
self._data.quat_w_opengl = torch.zeros((self._view.count, 4), device=self._device) self._data.quat_w_opengl = torch.zeros_like(self._data.quat_w_ros)
# -- intrinsic matrix # -- intrinsic matrix
self._data.intrinsic_matrices = torch.zeros((self._view.count, 3, 3), device=self._device) self._data.intrinsic_matrices = torch.zeros((self._view.count, 3, 3), device=self._device)
self._data.image_shape = self.image_shape self._data.image_shape = self.image_shape
...@@ -551,12 +561,8 @@ class Camera(SensorBase): ...@@ -551,12 +561,8 @@ class Camera(SensorBase):
self._data.quat_w_opengl[env_ids] = quat_opengl self._data.quat_w_opengl[env_ids] = quat_opengl
# save world and ros convention # save world and ros convention
self._data.quat_w_world[env_ids] = convert_orientation_convention( self._data.quat_w_world[env_ids] = convert_orientation_convention(quat_opengl, origin="opengl", target="world")
quat_opengl.clone(), origin="opengl", target="world" self._data.quat_w_ros[env_ids] = convert_orientation_convention(quat_opengl, origin="opengl", target="ros")
)
self._data.quat_w_ros[env_ids] = convert_orientation_convention(
quat_opengl.clone(), origin="opengl", target="ros"
)
def _create_annotator_data(self): def _create_annotator_data(self):
"""Create the buffers to store the annotator data. """Create the buffers to store the annotator data.
......
...@@ -321,7 +321,7 @@ def convert_orientation_convention( ...@@ -321,7 +321,7 @@ def convert_orientation_convention(
torch.Tensor: Quaternion of form `(w, x, y, z)` with shape (..., 4) in target convention torch.Tensor: Quaternion of form `(w, x, y, z)` with shape (..., 4) in target convention
""" """
if target == origin: if target == origin:
return orientation return orientation.clone()
# -- unify input type # -- unify input type
if origin == "ros": if origin == "ros":
...@@ -363,4 +363,4 @@ def convert_orientation_convention( ...@@ -363,4 +363,4 @@ def convert_orientation_convention(
) )
return math_utils.quat_from_matrix(rotm) return math_utils.quat_from_matrix(rotm)
else: else:
return quat_gl return quat_gl.clone()
...@@ -33,8 +33,8 @@ class PinholeCameraCfg(SpawnerCfg): ...@@ -33,8 +33,8 @@ class PinholeCameraCfg(SpawnerCfg):
Note: Note:
Currently only "pinhole" is supported. Currently only "pinhole" is supported.
""" """
clipping_range: tuple[float, float] = (1.0, 1000000.0) clipping_range: tuple[float, float] = (1.0, 1e6)
"""Near and far clipping distances (in m). Defaults to (1.0, 1000000.0).""" """Near and far clipping distances (in m). Defaults to (1.0, 1e6)."""
focal_length: float = 24.0 focal_length: float = 24.0
"""Perspective focal length (in cm). Defaults to 24.0cm. """Perspective focal length (in cm). Defaults to 24.0cm.
......
...@@ -190,7 +190,8 @@ class TerrainImporter: ...@@ -190,7 +190,8 @@ class TerrainImporter:
if key in self.meshes: if key in self.meshes:
raise ValueError(f"Mesh with key {key} already exists. Existing keys: {self.meshes.keys()}.") raise ValueError(f"Mesh with key {key} already exists. Existing keys: {self.meshes.keys()}.")
# add the prim path # add the prim path
prim_utils.create_prim(self.cfg.prim_path + f"/{key}", usd_path=usd_path) cfg = sim_utils.UsdFileCfg(usd_path=usd_path)
cfg.func(self.cfg.prim_path + f"/{key}", cfg)
# traverse the prim and get the collision mesh # traverse the prim and get the collision mesh
# THINK: Should the user specify the collision mesh? # THINK: Should the user specify the collision mesh?
......
...@@ -12,7 +12,8 @@ Some of these are imported from the module `omni.isaac.core.utils.torch` for con ...@@ -12,7 +12,8 @@ Some of these are imported from the module `omni.isaac.core.utils.torch` for con
import numpy as np import numpy as np
import torch import torch
import torch.nn.functional import torch.nn.functional
from typing import Optional, Sequence, Tuple, Union from typing import Optional, Tuple, Union
from typing_extensions import Literal
from omni.isaac.core.utils.torch.maths import normalize, scale_transform, unscale_transform from omni.isaac.core.utils.torch.maths import normalize, scale_transform, unscale_transform
from omni.isaac.core.utils.torch.rotations import ( from omni.isaac.core.utils.torch.rotations import (
...@@ -135,6 +136,7 @@ def matrix_from_quat(quaternions: torch.Tensor) -> torch.Tensor: ...@@ -135,6 +136,7 @@ def matrix_from_quat(quaternions: torch.Tensor) -> torch.Tensor:
Args: Args:
quaternions: quaternions with real part first, quaternions: quaternions with real part first,
as tensor of shape (..., 4). as tensor of shape (..., 4).
Returns: Returns:
Rotation matrices as tensor of shape (..., 3, 3). Rotation matrices as tensor of shape (..., 3, 3).
...@@ -162,42 +164,52 @@ def matrix_from_quat(quaternions: torch.Tensor) -> torch.Tensor: ...@@ -162,42 +164,52 @@ def matrix_from_quat(quaternions: torch.Tensor) -> torch.Tensor:
return o.reshape(quaternions.shape[:-1] + (3, 3)) return o.reshape(quaternions.shape[:-1] + (3, 3))
def convert_quat(quat: Union[torch.Tensor, Sequence[float]], to: Optional[str] = "xyzw") -> torch.Tensor: def convert_quat(
quat: Union[torch.Tensor, np.ndarray], to: Literal["xyzw", "wxyz"] = "xyzw"
) -> Union[torch.Tensor, np.ndarray]:
"""Converts quaternion from one convention to another. """Converts quaternion from one convention to another.
The convention to convert TO is specified as an optional argument. If to == 'xyzw', The convention to convert TO is specified as an optional argument. If to == 'xyzw',
then the input is in 'wxyz' format, and vice-versa. then the input is in 'wxyz' format, and vice-versa.
Args: Args:
quat (Union[torch.Tensor, Sequence[float]]): Input quaternion of shape (..., 4). quat (Union[torch.Tensor, np.ndarray]): Input quaternion of shape (..., 4).
to (Optional[str], optional): Convention to convert quaternion to.. Defaults to "xyzw". to (Literal["xyzw", "wxyz"], optional): Convention to convert quaternion to.. Defaults to "xyzw".
Returns:
Union[torch.Tensor, np.ndarray]: The converted quaternion in specified convention.
Raises: Raises:
ValueError: Invalid input argument `to`, i.e. not "xyzw" or "wxyz". ValueError: Invalid input argument `to`, i.e. not "xyzw" or "wxyz".
ValueError: Invalid shape of input `quat`, i.e. not (..., 4,). ValueError: Invalid shape of input `quat`, i.e. not (..., 4,).
Returns:
torch.Tensor: The converted quaternion in specified convention.
""" """
# convert to torch (sanity check)
if not isinstance(quat, torch.Tensor):
if isinstance(quat, np.ndarray):
quat = torch.from_numpy(quat)
else:
quat = torch.tensor(quat, dtype=float)
# check input is correct # check input is correct
if quat.shape[-1] != 4: if quat.shape[-1] != 4:
msg = f"Expected input quaternion shape mismatch: {quat.shape} != (..., 4)." msg = f"Expected input quaternion shape mismatch: {quat.shape} != (..., 4)."
raise ValueError(msg) raise ValueError(msg)
# convert to specified quaternion type if to not in ["xyzw", "wxyz"]:
if to == "xyzw": msg = f"Expected input argument `to` to be 'xyzw' or 'wxyz'. Received: {to}."
# wxyz -> xyzw raise ValueError(msg)
return quat.roll(-1, dims=-1) # check if input is numpy array (we support this backend since some classes use numpy)
elif to == "wxyz": if isinstance(quat, np.ndarray):
# xyzw -> wxyz # use numpy functions
return quat.roll(1, dims=-1) if to == "xyzw":
# wxyz -> xyzw
return np.roll(quat, -1, axis=-1)
else:
# xyzw -> wxyz
return np.roll(quat, 1, axis=-1)
else: else:
raise ValueError(f"Choose a valid `to` argument (xyzw or wxyz). Received: {to}") # convert to torch (sanity check)
if not isinstance(quat, torch.Tensor):
quat = torch.tensor(quat, dtype=float)
# convert to specified quaternion type
if to == "xyzw":
# wxyz -> xyzw
return quat.roll(-1, dims=-1)
else:
# xyzw -> wxyz
return quat.roll(1, dims=-1)
@torch.jit.script @torch.jit.script
...@@ -245,9 +257,7 @@ def quat_from_euler_xyz(roll: torch.Tensor, pitch: torch.Tensor, yaw: torch.Tens ...@@ -245,9 +257,7 @@ def quat_from_euler_xyz(roll: torch.Tensor, pitch: torch.Tensor, yaw: torch.Tens
@torch.jit.script @torch.jit.script
def _sqrt_positive_part(x: torch.Tensor) -> torch.Tensor: def _sqrt_positive_part(x: torch.Tensor) -> torch.Tensor:
""" """Returns torch.sqrt(torch.max(0, x)) but with a zero sub-gradient where x is 0.
Returns torch.sqrt(torch.max(0, x))
but with a zero subgradient where x is 0.
Reference: Reference:
Based on PyTorch3D (https://github.com/facebookresearch/pytorch3d/blob/main/pytorch3d/transforms/rotation_conversions.py#L91-L99) Based on PyTorch3D (https://github.com/facebookresearch/pytorch3d/blob/main/pytorch3d/transforms/rotation_conversions.py#L91-L99)
...@@ -323,13 +333,12 @@ def quat_from_matrix(matrix: torch.Tensor) -> torch.Tensor: ...@@ -323,13 +333,12 @@ def quat_from_matrix(matrix: torch.Tensor) -> torch.Tensor:
def _axis_angle_rotation(axis: str, angle: torch.Tensor) -> torch.Tensor: def _axis_angle_rotation(axis: str, angle: torch.Tensor) -> torch.Tensor:
""" """Return the rotation matrices for one of the rotations about an axis of which Euler angles describe,
Return the rotation matrices for one of the rotations about an axis for each value of the angle given.
of which Euler angles describe, for each value of the angle given.
Args: Args:
axis: Axis label "X" or "Y or "Z". axis: Axis label "X" or "Y or "Z".
angle: any shape tensor of Euler angles in radians angle: Any shape tensor of Euler angles in radians.
Returns: Returns:
Rotation matrices as tensor of shape (..., 3, 3). Rotation matrices as tensor of shape (..., 3, 3).
......
...@@ -36,7 +36,7 @@ from omni.isaac.core.utils.torch import set_seed ...@@ -36,7 +36,7 @@ from omni.isaac.core.utils.torch import set_seed
from omni.isaac.core.utils.viewports import set_camera_view from omni.isaac.core.utils.viewports import set_camera_view
from pxr import Gf, UsdGeom from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.sensors.camera import Camera, PinholeCameraCfg from omni.isaac.orbit.compat.sensors.camera import Camera, PinholeCameraCfg
from omni.isaac.orbit.utils.math import convert_quat from omni.isaac.orbit.utils.math import convert_quat
from omni.isaac.orbit.utils.timer import Timer from omni.isaac.orbit.utils.timer import Timer
......
...@@ -33,7 +33,7 @@ from omni.isaac.core.objects.cuboid import DynamicCuboid ...@@ -33,7 +33,7 @@ from omni.isaac.core.objects.cuboid import DynamicCuboid
from omni.isaac.core.simulation_context import SimulationContext from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.sensors.height_scanner import HeightScanner, HeightScannerCfg from omni.isaac.orbit.compat.sensors.height_scanner import HeightScanner, HeightScannerCfg
from omni.isaac.orbit.compat.sensors.height_scanner.utils import create_points_from_grid, plot_height_grid from omni.isaac.orbit.compat.sensors.height_scanner.utils import create_points_from_grid, plot_height_grid
from omni.isaac.orbit.utils.math import convert_quat from omni.isaac.orbit.utils.math import convert_quat
......
...@@ -21,7 +21,7 @@ import omni.isaac.core.utils.stage as stage_utils ...@@ -21,7 +21,7 @@ import omni.isaac.core.utils.stage as stage_utils
from omni.isaac.core.simulation_context import SimulationContext from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script shows the issue with renderer in Isaac Sim that affects episodic resets.
The first few images of every new episode are not updated. They take multiple steps to update
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
# run with anymal
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/isaacsim/check_camera.py --scenario anymal
```
"""
"""Launch Isaac Sim Simulator first."""
import argparse
# omni-isaac-orbit
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser(
description="This script shows the issue with renderer in Isaac Sim that affects episodic resets."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.")
parser.add_argument("--scenario", type=str, default="anymal", help="Scenario to load.", choices=["anymal", "cube"])
args_cli = parser.parse_args()
# launch omniverse app
config = {"headless": args_cli.headless}
simulation_app = SimulationApp(config)
"""Rest everything follows."""
import numpy as np
import os
import random
import omni.isaac.core.utils.nucleus as nucleus_utils
import omni.isaac.core.utils.prims as prim_utils
import omni.replicator.core as rep
from omni.isaac.core.articulations import ArticulationView
from omni.isaac.core.prims import GeometryPrim, RigidPrim, RigidPrimView
from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view
from omni.isaac.core.world import World
from PIL import Image, ImageChops
from pxr import Gf, UsdGeom
# check nucleus connection
if nucleus_utils.get_assets_root_path() is None:
msg = (
"Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n"
"\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus"
)
raise RuntimeError(msg)
ISAAC_NUCLEUS_DIR = f"{nucleus_utils.get_assets_root_path()}/Isaac"
"""Path to the `Isaac` directory on the NVIDIA Nucleus Server."""
def main():
"""Runs a camera sensor from orbit."""
# Load kit helper
world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu")
# Set main camera
set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Enable flatcache which avoids passing data over to USD structure
# this speeds up the read-write operation of GPU buffers
if world.get_physics_context().use_gpu_pipeline:
world.get_physics_context().enable_flatcache(True)
# Enable hydra scene-graph instancing
# this is needed to visualize the scene when flatcache is enabled
set_carb_setting(world._settings, "/persistent/omnihydra/useSceneGraphInstancing", True)
# Populate scene
# Ground
world.scene.add_default_ground_plane()
# Lights-1
prim_utils.create_prim(
"/World/Light/GreySphere",
"SphereLight",
translation=(4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (0.75, 0.75, 0.75)},
)
# Lights-2
prim_utils.create_prim(
"/World/Light/WhiteSphere",
"SphereLight",
translation=(-4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (1.0, 1.0, 1.0)},
)
# Xform to hold objects
if args_cli.scenario == "cube":
prim_utils.create_prim("/World/Objects", "Xform")
# Random objects
for i in range(8):
# sample random position
position = np.random.rand(3) - np.asarray([0.05, 0.05, -1.0])
position *= np.asarray([1.5, 1.5, 0.5])
# create prim
prim_type = random.choice(["Cube", "Sphere", "Cylinder"])
_ = prim_utils.create_prim(
f"/World/Objects/Obj_{i:02d}",
prim_type,
translation=position,
scale=(0.25, 0.25, 0.25),
semantic_label=prim_type,
)
# add rigid properties
GeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True)
rigid_obj = RigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0)
# cast to geom prim
geom_prim = getattr(UsdGeom, prim_type)(rigid_obj.prim)
# set random color
color = Gf.Vec3f(random.random(), random.random(), random.random())
geom_prim.CreateDisplayColorAttr()
geom_prim.GetDisplayColorAttr().Set([color])
# Setup camera sensor on the world
cam_prim_path = "/World/CameraSensor"
else:
# Robot
prim_utils.create_prim(
"/World/Robot",
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_instanceable.usd",
translation=(0.0, 0.0, 0.6),
)
# Setup camera sensor on the robot
cam_prim_path = "/World/CameraSensor"
# Create camera
cam_prim = prim_utils.create_prim(
cam_prim_path,
prim_type="Camera",
translation=(5.0, 5.0, 5.0),
orientation=(0.33985113, 0.17591988, 0.42470818, 0.82047324),
)
_ = UsdGeom.Camera(cam_prim)
# Get render product
render_prod_path = rep.create.render_product(cam_prim_path, resolution=(640, 480))
# create annotator node
rep_registry = {}
for name in ["rgb", "distance_to_image_plane"]:
# create annotator
rep_annotator = rep.AnnotatorRegistry.get_annotator(name, device="cpu")
rep_annotator.attach(render_prod_path)
# add to registry
rep_registry[name] = rep_annotator
# Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera", args_cli.scenario)
os.makedirs(output_dir, exist_ok=True)
# Create a view of the stuff we want to see
if args_cli.scenario == "cube":
view: RigidPrimView = world.scene.add(RigidPrimView("/World/Objects/.*", name="my_object"))
else:
view: ArticulationView = world.scene.add(ArticulationView("/World/Robot", name="my_object"))
# Play simulator
world.reset()
# Get initial state
if args_cli.scenario == "cube":
initial_pos, initial_quat = view.get_world_poses()
initial_joint_pos = None
initial_joint_vel = None
else:
initial_pos, initial_quat = view.get_world_poses()
initial_joint_pos = view.get_joint_positions()
initial_joint_vel = view.get_joint_velocities()
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
for _ in range(5):
world.step(render=True)
# Counter
count = 0
prev_im = None
# make episode directory
episode_count = 0
episode_dir = os.path.join(output_dir, f"episode_{episode_count:06d}")
os.makedirs(episode_dir, exist_ok=True)
# Simulate physics
while simulation_app.is_running():
# If simulation is stopped, then exit.
if world.is_stopped():
break
# If simulation is paused, then skip.
if not world.is_playing():
world.step(render=not args_cli.headless)
continue
# Reset on intervals
if count % 25 == 0:
# reset all the state
view.set_world_poses(initial_pos, initial_quat)
if initial_joint_pos is not None:
view.set_joint_positions(initial_joint_pos)
if initial_joint_vel is not None:
view.set_joint_velocities(initial_joint_vel)
# make a new episode directory
episode_dir = os.path.join(output_dir, f"episode_{episode_count:06d}")
os.makedirs(episode_dir, exist_ok=True)
# reset counters
count = 0
episode_count += 1
# Step simulation
for _ in range(15):
world.step(render=False)
world.render()
# Update camera data
rgb_data = rep_registry["rgb"].get_data()
depth_data = rep_registry["distance_to_image_plane"].get_data()
# Show current image number
print(f"[Epi {episode_count:03d}] Current image number: {count:06d}")
# Save data
curr_im = Image.fromarray(rgb_data)
curr_im.save(os.path.join(episode_dir, f"{count:06d}_rgb.png"))
# Save diff
if prev_im is not None:
diff_im = ImageChops.difference(curr_im, prev_im)
# convert to grayscale and threshold
diff_im = diff_im.convert("L")
threshold = 30
diff_im = diff_im.point(lambda p: p > threshold and 255)
# Save all of them together
dst_im = Image.new("RGB", (curr_im.width + prev_im.width + diff_im.width, diff_im.height))
dst_im.paste(prev_im, (0, 0))
dst_im.paste(curr_im, (prev_im.width, 0))
dst_im.paste(diff_im, (2 * prev_im.width, 0))
dst_im.save(os.path.join(episode_dir, f"{count:06d}_diff.png"))
# Save to previous
prev_im = curr_im.copy()
# Update counter
count += 1
# Print camera info
print("Received shape of rgb image: ", rgb_data.shape)
print("Received shape of depth image: ", depth_data.shape)
print("-------------------------------")
if __name__ == "__main__":
# Runs the main function
main()
# Close the simulator
simulation_app.close()
...@@ -17,7 +17,9 @@ import argparse ...@@ -17,7 +17,9 @@ import argparse
from omni.isaac.kit import SimulationApp from omni.isaac.kit import SimulationApp
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(
description="This script shows the issue in Isaac Sim with GPU simulation of floating robots."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--num_robots", type=int, default=128, help="Number of robots to spawn.") parser.add_argument("--num_robots", type=int, default=128, help="Number of robots to spawn.")
parser.add_argument( parser.add_argument(
......
...@@ -19,7 +19,9 @@ import argparse ...@@ -19,7 +19,9 @@ import argparse
from omni.isaac.kit import SimulationApp from omni.isaac.kit import SimulationApp
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(
description="This script shows how to use replicator to randomly change the textures of a USD scene."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
args_cli = parser.parse_args() args_cli = parser.parse_args()
......
...@@ -59,7 +59,7 @@ class TestUsdVisualizationMarkers(unittest.TestCase): ...@@ -59,7 +59,7 @@ class TestUsdVisualizationMarkers(unittest.TestCase):
# check number of markers # check number of markers
self.assertEqual(test_marker.num_prototypes, 1) self.assertEqual(test_marker.num_prototypes, 1)
def test_usd_cpu_marker(self): def test_usd_marker(self):
"""Test with marker from a USD.""" """Test with marker from a USD."""
# create a marker # create a marker
test_marker = VisualizationMarkers("/World/Visuals/test_frames", FRAME_MARKER_CFG) test_marker = VisualizationMarkers("/World/Visuals/test_frames", FRAME_MARKER_CFG)
...@@ -82,29 +82,6 @@ class TestUsdVisualizationMarkers(unittest.TestCase): ...@@ -82,29 +82,6 @@ class TestUsdVisualizationMarkers(unittest.TestCase):
# asset that count is correct # asset that count is correct
self.assertEqual(test_marker.count, num_frames) self.assertEqual(test_marker.count, num_frames)
def test_usd_gpu_marker(self):
"""Test with marker from a USD."""
# create a marker
test_marker = VisualizationMarkers("/World/Visuals/test_frames", FRAME_MARKER_CFG)
# play the simulation
self.sim.reset()
# create a buffer
num_frames = 0
# run with randomization of poses
for count in range(1000):
# sample random poses
if count % 50 == 0:
num_frames = torch.randint(10, 1000, (1,)).item()
frame_translations = torch.randn((num_frames, 3), device=self.sim.device)
frame_rotations = random_orientation(num_frames, device=self.sim.device)
# set the marker
test_marker.visualize(translations=frame_translations, orientations=frame_rotations)
# update the kit
self.sim.step()
# asset that count is correct
self.assertEqual(test_marker.count, num_frames)
def test_usd_marker_color(self): def test_usd_marker_color(self):
"""Test with marker from a USD with its color modified.""" """Test with marker from a USD with its color modified."""
# create a marker # create a marker
......
...@@ -34,16 +34,15 @@ simulation_app = SimulationApp(config) ...@@ -34,16 +34,15 @@ simulation_app = SimulationApp(config)
import torch import torch
import carb
import omni.isaac.core.utils.prims as prim_utils import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.cloner import GridCloner from omni.isaac.cloner import GridCloner
from omni.isaac.core.simulation_context import SimulationContext from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.carb import set_carb_setting from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.assets import Articulation from omni.isaac.orbit.assets import Articulation
from omni.isaac.orbit.assets.articulation.config.anymal import ANYMAL_C_CFG from omni.isaac.orbit.assets.config.anymal import ANYMAL_C_CFG
from omni.isaac.orbit.sensors.contact_sensor import ContactSensor, ContactSensorCfg from omni.isaac.orbit.sensors.contact_sensor import ContactSensor, ContactSensorCfg
""" """
...@@ -129,7 +128,8 @@ def main(): ...@@ -129,7 +128,8 @@ def main():
# Define simulation stepping # Define simulation stepping
decimation = 4 decimation = 4
sim_dt = decimation * sim.get_physics_dt() physics_dt = sim.get_physics_dt()
sim_dt = decimation * physics_dt
sim_time = 0.0 sim_time = 0.0
count = 0 count = 0
# Simulate physics # Simulate physics
...@@ -153,19 +153,18 @@ def main(): ...@@ -153,19 +153,18 @@ def main():
# perform 4 steps # perform 4 steps
for _ in range(decimation): for _ in range(decimation):
# apply actions # apply actions
robot.set_joint_position_targets(robot.data.default_joint_pos) robot.set_joint_position_target(robot.data.default_joint_pos)
# write commands to sim # write commands to sim
robot.write_data_to_sim() robot.write_data_to_sim()
# perform step # perform step
sim.step(render=not args_cli.headless) sim.step(render=not args_cli.headless)
# fetch data # fetch data
robot.fetch_data_from_sim() robot.update(physics_dt)
# update sim-time # update sim-time
sim_time += sim_dt sim_time += sim_dt
count += 1 count += 1
# update the buffers # update the buffers
if sim.is_playing(): if sim.is_playing():
robot.update(sim_dt)
contact_sensor.update(sim_dt, force_recompute=True) contact_sensor.update(sim_dt, force_recompute=True)
if count % 100 == 0: if count % 100 == 0:
print("Sim-time: ", sim_time) print("Sim-time: ", sim_time)
......
...@@ -3,10 +3,21 @@ ...@@ -3,10 +3,21 @@
# #
# SPDX-License-Identifier: BSD-3-Clause # SPDX-License-Identifier: BSD-3-Clause
import argparse """Launch Isaac Sim Simulator first."""
import matplotlib.pyplot as plt
import numpy as np
import os import os
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app
# note: we only need to do this because of `TerrainImporter` which uses Omniverse functions
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
app_launcher = AppLauncher(headless=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
import argparse
import trimesh import trimesh
import omni.isaac.orbit.terrains.height_field as hf_gen import omni.isaac.orbit.terrains.height_field as hf_gen
...@@ -242,3 +253,6 @@ if __name__ == "__main__": ...@@ -242,3 +253,6 @@ if __name__ == "__main__":
test_discrete_obstacles_terrain(difficulty=0.25, obstacle_height_mode="fixed") test_discrete_obstacles_terrain(difficulty=0.25, obstacle_height_mode="fixed")
test_wave_terrain(difficulty=0.25) test_wave_terrain(difficulty=0.25)
test_stepping_stones_terrain(difficulty=1.0) test_stepping_stones_terrain(difficulty=1.0)
# close the app
simulation_app.close()
...@@ -3,8 +3,21 @@ ...@@ -3,8 +3,21 @@
# #
# SPDX-License-Identifier: BSD-3-Clause # SPDX-License-Identifier: BSD-3-Clause
import argparse """Launch Isaac Sim Simulator first."""
import os import os
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app
# note: we only need to do this because of `TerrainImporter` which uses Omniverse functions
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
app_launcher = AppLauncher(headless=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
import argparse
import trimesh import trimesh
import omni.isaac.orbit.terrains.trimesh as mesh_gen import omni.isaac.orbit.terrains.trimesh as mesh_gen
...@@ -404,3 +417,6 @@ if __name__ == "__main__": ...@@ -404,3 +417,6 @@ if __name__ == "__main__":
test_repeated_objects_terrain(difficulty=0.75, object_type="pyramid") test_repeated_objects_terrain(difficulty=0.75, object_type="pyramid")
test_repeated_objects_terrain(difficulty=0.75, object_type="cylinder") test_repeated_objects_terrain(difficulty=0.75, object_type="cylinder")
test_repeated_objects_terrain(difficulty=0.75, object_type="box") test_repeated_objects_terrain(difficulty=0.75, object_type="box")
# close the app
simulation_app.close()
...@@ -3,9 +3,21 @@ ...@@ -3,9 +3,21 @@
# #
# SPDX-License-Identifier: BSD-3-Clause # SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
import argparse
import os import os
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app
# note: we only need to do this because of `TerrainImporter` which uses Omniverse functions
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
app_launcher = AppLauncher(headless=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
import shutil import shutil
from omni.isaac.orbit.terrains.config.rough import ROUGH_TERRAINS_CFG from omni.isaac.orbit.terrains.config.rough import ROUGH_TERRAINS_CFG
...@@ -26,3 +38,6 @@ if __name__ == "__main__": ...@@ -26,3 +38,6 @@ if __name__ == "__main__":
ROUGH_TERRAINS_CFG.curriculum = False ROUGH_TERRAINS_CFG.curriculum = False
# generate terrains # generate terrains
terrain_generator = TerrainGenerator(cfg=ROUGH_TERRAINS_CFG) terrain_generator = TerrainGenerator(cfg=ROUGH_TERRAINS_CFG)
# close the simulation app
simulation_app.close()
...@@ -33,7 +33,7 @@ import argparse ...@@ -33,7 +33,7 @@ import argparse
from omni.isaac.kit import SimulationApp from omni.isaac.kit import SimulationApp
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="This script shows how to use the terrain importer.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--geom_sphere", action="store_true", default=False, help="Whether to use sphere mesh or shape.") parser.add_argument("--geom_sphere", action="store_true", default=False, help="Whether to use sphere mesh or shape.")
parser.add_argument( parser.add_argument(
......
...@@ -13,7 +13,7 @@ import omni.isaac.core.utils.prims as prim_utils ...@@ -13,7 +13,7 @@ import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.torch as torch_utils import omni.isaac.core.utils.torch as torch_utils
from omni.isaac.core.articulations import ArticulationView from omni.isaac.core.articulations import ArticulationView
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg
......
...@@ -12,7 +12,7 @@ import omni.isaac.core.utils.nucleus as nucleus_utils ...@@ -12,7 +12,7 @@ import omni.isaac.core.utils.nucleus as nucleus_utils
import omni.isaac.core.utils.prims as prim_utils import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.core.articulations import ArticulationView from omni.isaac.core.articulations import ArticulationView
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg
......
...@@ -13,7 +13,7 @@ import omni.isaac.core.utils.prims as prim_utils ...@@ -13,7 +13,7 @@ import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.torch as torch_utils import omni.isaac.core.utils.torch as torch_utils
from omni.isaac.core.articulations import ArticulationView from omni.isaac.core.articulations import ArticulationView
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg
......
...@@ -10,7 +10,7 @@ from typing import List ...@@ -10,7 +10,7 @@ from typing import List
import omni.isaac.core.utils.prims as prim_utils import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import StaticMarker from omni.isaac.orbit.compat.markers import StaticMarker
from omni.isaac.orbit.compat.utils.mdp import ObservationManager, RewardManager from omni.isaac.orbit.compat.utils.mdp import ObservationManager, RewardManager
from omni.isaac.orbit.controllers.differential_inverse_kinematics import DifferentialInverseKinematics from omni.isaac.orbit.controllers.differential_inverse_kinematics import DifferentialInverseKinematics
......
...@@ -9,7 +9,7 @@ import torch ...@@ -9,7 +9,7 @@ import torch
import omni.isaac.core.utils.prims as prim_utils import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import PointMarker, StaticMarker from omni.isaac.orbit.compat.markers import PointMarker, StaticMarker
from omni.isaac.orbit.compat.utils.mdp import ObservationManager, RewardManager from omni.isaac.orbit.compat.utils.mdp import ObservationManager, RewardManager
from omni.isaac.orbit.controllers.differential_inverse_kinematics import DifferentialInverseKinematics from omni.isaac.orbit.controllers.differential_inverse_kinematics import DifferentialInverseKinematics
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script shows how to use the camera sensor from the Orbit framework.
The camera sensor is created and interfaced through the Omniverse Replicator API. However, instead of using
the simulator or OpenGL convention for the camera, we use the robotics or ROS convention.
"""
"""Launch Isaac Sim Simulator first."""
import argparse
# omni-isaac-orbit
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.")
parser.add_argument("--draw", action="store_true", default=False, help="Draw the obtained pointcloud on viewport.")
args_cli = parser.parse_args()
# launch omniverse app
config = {"headless": args_cli.headless}
simulation_app = SimulationApp(config)
"""Rest everything follows."""
import numpy as np
import os
import random
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.debug_draw._debug_draw as omni_debug_draw
import omni.replicator.core as rep
from omni.isaac.core.prims import RigidPrim
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.compat.sensors.camera import Camera, PinholeCameraCfg
from omni.isaac.orbit.sensors.camera.utils import create_pointcloud_from_rgbd
from omni.isaac.orbit.utils import convert_dict_to_backend
"""
Helpers
"""
def design_scene():
"""Add prims to the scene."""
# Ground-plane
kit_utils.create_ground_plane("/World/defaultGroundPlane")
# Lights-1
prim_utils.create_prim(
"/World/Light/GreySphere",
"SphereLight",
translation=(4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (0.75, 0.75, 0.75)},
)
# Lights-2
prim_utils.create_prim(
"/World/Light/WhiteSphere",
"SphereLight",
translation=(-4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (1.0, 1.0, 1.0)},
)
# Xform to hold objects
prim_utils.create_prim("/World/Objects", "Xform")
# Random objects
for i in range(8):
# sample random position
position = np.random.rand(3) - np.asarray([0.05, 0.05, -1.0])
position *= np.asarray([1.5, 1.5, 0.5])
# create prim
prim_type = random.choice(["Cube", "Sphere", "Cylinder"])
_ = prim_utils.create_prim(
f"/World/Objects/Obj_{i:02d}",
prim_type,
translation=position,
scale=(0.25, 0.25, 0.25),
semantic_label=prim_type,
)
# add rigid properties
rigid_obj = RigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0)
# cast to geom prim
geom_prim = getattr(UsdGeom, prim_type)(rigid_obj.prim)
# set random color
color = Gf.Vec3f(random.random(), random.random(), random.random())
geom_prim.CreateDisplayColorAttr()
geom_prim.GetDisplayColorAttr().Set([color])
"""
Main
"""
def main():
"""Runs a camera sensor from orbit."""
# Load kit helper
sim = SimulationContext(physics_dt=0.005, rendering_dt=0.005, backend="torch")
# Set main camera
set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Acquire draw interface
draw_interface = omni_debug_draw.acquire_debug_draw_interface()
# Populate scene
design_scene()
# Setup camera sensor
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors"],
usd_params=PinholeCameraCfg.UsdCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
),
)
camera = Camera(cfg=camera_cfg, device="cuda" if args_cli.gpu else "cpu")
# Spawn camera
camera.spawn("/World/CameraSensor")
# Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera")
rep_writer = rep.BasicWriter(output_dir=output_dir, frame_padding=3)
# Play simulator
sim.play()
# Initialize camera
camera.initialize()
# Set pose: There are two ways to set the pose of the camera.
# -- Option-1: Set pose using view
# camera.set_world_pose_from_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# -- Option-2: Set pose using ROS
position = [2.5, 2.5, 2.5]
orientation = [-0.17591989, 0.33985114, 0.82047325, -0.42470819]
camera.set_world_pose_ros(position, orientation)
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
for _ in range(3):
sim.step()
# Simulate physics
while simulation_app.is_running():
# If simulation is stopped, then exit.
if sim.is_stopped():
break
# If simulation is paused, then skip.
if not sim.is_playing():
sim.step(render=not args_cli.headless)
continue
# Step simulation
sim.step()
# Update camera data
camera.update(dt=0.0)
# Print camera info
print(camera)
print("Received shape of rgb image: ", camera.data.output["rgb"].shape)
print("Received shape of depth image: ", camera.data.output["distance_to_image_plane"].shape)
print("-------------------------------")
# Save images
# note: BasicWriter only supports saving data in numpy format
rep_writer.write(convert_dict_to_backend(camera.data.output, backend="numpy"))
# Pointcloud in world frame
pointcloud_w, pointcloud_rgb = create_pointcloud_from_rgbd(
camera.data.intrinsic_matrix,
depth=camera.data.output["distance_to_image_plane"],
rgb=camera.data.output["rgb"],
position=camera.data.position,
orientation=camera.data.orientation,
normalize_rgb=True,
num_channels=4,
)
# Draw pointcloud
if not args_cli.headless and args_cli.draw:
# Convert to numpy for visualization
if not isinstance(pointcloud_w, np.ndarray):
pointcloud_w = pointcloud_w.cpu().numpy()
if not isinstance(pointcloud_rgb, np.ndarray):
pointcloud_rgb = pointcloud_rgb.cpu().numpy()
# Visualize the points
num_points = pointcloud_w.shape[0]
points_size = [1.25] * num_points
points_color = pointcloud_rgb
draw_interface.clear_points()
draw_interface.draw_points(pointcloud_w.tolist(), points_color, points_size)
if __name__ == "__main__":
# Runs the main function
main()
# Close the simulator
simulation_app.close()
...@@ -17,7 +17,7 @@ import argparse ...@@ -17,7 +17,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="This script demonstrates how to use the camera sensor.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.") parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.")
parser.add_argument("--draw", action="store_true", default=False, help="Draw the obtained pointcloud on viewport.") parser.add_argument("--draw", action="store_true", default=False, help="Draw the obtained pointcloud on viewport.")
...@@ -43,8 +43,8 @@ from omni.isaac.core.simulation_context import SimulationContext ...@@ -43,8 +43,8 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view from omni.isaac.core.utils.viewports import set_camera_view
from pxr import Gf, UsdGeom from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.sensors.camera import Camera, PinholeCameraCfg from omni.isaac.orbit.sensors.camera import Camera, CameraCfg
from omni.isaac.orbit.utils import convert_dict_to_backend from omni.isaac.orbit.utils import convert_dict_to_backend
from omni.isaac.orbit.utils.math import project_points, transform_points, unproject_depth from omni.isaac.orbit.utils.math import project_points, transform_points, unproject_depth
...@@ -55,22 +55,16 @@ Helpers ...@@ -55,22 +55,16 @@ Helpers
def design_scene(): def design_scene():
"""Add prims to the scene.""" """Add prims to the scene."""
# Spawn things into stage
# Ground-plane # Ground-plane
kit_utils.create_ground_plane("/World/defaultGroundPlane") cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg)
# Lights-1 # Lights-1
prim_utils.create_prim( cfg = sim_utils.SphereLightCfg(intensity=600.0, color=(0.75, 0.75, 0.75), radius=2.5)
"/World/Light/GreySphere", cfg.func("/World/Light/greyLight", cfg, translation=(4.5, 3.5, 10.0))
"SphereLight",
translation=(4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (0.75, 0.75, 0.75)},
)
# Lights-2 # Lights-2
prim_utils.create_prim( cfg = sim_utils.SphereLightCfg(intensity=600.0, color=(1.0, 1.0, 1.0), radius=2.5)
"/World/Light/WhiteSphere", cfg.func("/World/Light/whiteSphere", cfg, translation=(-4.5, 3.5, 10.0))
"SphereLight",
translation=(-4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (1.0, 1.0, 1.0)},
)
# Xform to hold objects # Xform to hold objects
prim_utils.create_prim("/World/Objects", "Xform") prim_utils.create_prim("/World/Objects", "Xform")
# Random objects # Random objects
...@@ -109,7 +103,6 @@ def main(): ...@@ -109,7 +103,6 @@ def main():
sim = SimulationContext( sim = SimulationContext(
physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda" if args_cli.gpu else "cpu" physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda" if args_cli.gpu else "cpu"
) )
# sim = SimulationContext(physics_dt=0.005, rendering_dt=0.005, backend="numpy")
# Set main camera # Set main camera
set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Acquire draw interface # Acquire draw interface
...@@ -118,20 +111,21 @@ def main(): ...@@ -118,20 +111,21 @@ def main():
# Populate scene # Populate scene
design_scene() design_scene()
# Setup camera sensor # Setup camera sensor
camera_cfg = PinholeCameraCfg( camera_cfg = CameraCfg(
prim_path="/World/CameraSensor_.*/Cam",
update_period=0, update_period=0,
height=480, height=480,
width=640, width=640,
data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors", "semantic_segmentation"], data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors", "semantic_segmentation"],
usd_params=PinholeCameraCfg.UsdCameraCfg( spawn=sim_utils.PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5) focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
), ),
) )
camera = Camera(cfg=camera_cfg) # Manually spawn the camera because we want to be fancy
camera_cfg.spawn.func("/World/CameraSensor_00/Cam", camera_cfg.spawn)
# Spawn camera camera_cfg.spawn.func("/World/CameraSensor_01/Cam", camera_cfg.spawn)
camera.spawn("/World/CameraSensor/Cam_00") # Create camera
camera.spawn("/World/CameraSensor/Cam_01") camera = Camera(cfg=camera_cfg.replace(spawn=None))
# Create replicator writer # Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera") output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera")
...@@ -139,8 +133,6 @@ def main(): ...@@ -139,8 +133,6 @@ def main():
# Play simulator # Play simulator
sim.play() sim.play()
# Initialize camera
camera.initialize("/World/CameraSensor/Cam_*")
# Set pose: There are two ways to set the pose of the camera. # Set pose: There are two ways to set the pose of the camera.
# -- Option-1: Set pose using view # -- Option-1: Set pose using view
...@@ -205,7 +197,7 @@ def main(): ...@@ -205,7 +197,7 @@ def main():
# Pointcloud in world frame # Pointcloud in world frame
points_3d_cam = unproject_depth(camera.data.output["distance_to_image_plane"], camera.data.intrinsic_matrices) points_3d_cam = unproject_depth(camera.data.output["distance_to_image_plane"], camera.data.intrinsic_matrices)
points_3d_world = transform_points(points_3d_cam, camera.data.position, camera.data.orientation) points_3d_world = transform_points(points_3d_cam, camera.data.pos_w, camera.data.quat_w_ros)
# Check methods are valid # Check methods are valid
im_height, im_width = camera.image_shape im_height, im_width = camera.image_shape
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="This script creates an empty stage in Isaac Sim.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
args_cli = parser.parse_args() args_cli = parser.parse_args()
......
...@@ -38,7 +38,7 @@ from omni.isaac.core.simulation_context import SimulationContext ...@@ -38,7 +38,7 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.carb import set_carb_setting from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import StaticMarker from omni.isaac.orbit.compat.markers import StaticMarker
from omni.isaac.orbit.controllers.differential_inverse_kinematics import ( from omni.isaac.orbit.controllers.differential_inverse_kinematics import (
DifferentialInverseKinematics, DifferentialInverseKinematics,
......
...@@ -17,7 +17,9 @@ import argparse ...@@ -17,7 +17,9 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(
description="This script demonstrates how to use the RMPFlow controller with the simulator."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--robot", type=str, default="ur10", help="Name of the robot. Options: franka_panda, ur10.") parser.add_argument("--robot", type=str, default="ur10", help="Name of the robot. Options: franka_panda, ur10.")
parser.add_argument("--num_envs", type=int, default=5, help="Number of environments to spawn.") parser.add_argument("--num_envs", type=int, default=5, help="Number of environments to spawn.")
...@@ -38,7 +40,7 @@ from omni.isaac.core.simulation_context import SimulationContext ...@@ -38,7 +40,7 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.carb import set_carb_setting from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import StaticMarker from omni.isaac.orbit.compat.markers import StaticMarker
from omni.isaac.orbit.controllers.config.rmp_flow import FRANKA_RMPFLOW_CFG, UR10_RMPFLOW_CFG from omni.isaac.orbit.controllers.config.rmp_flow import FRANKA_RMPFLOW_CFG, UR10_RMPFLOW_CFG
from omni.isaac.orbit.controllers.rmp_flow import RmpFlowController from omni.isaac.orbit.controllers.rmp_flow import RmpFlowController
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Random agent for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
...@@ -15,7 +15,7 @@ import argparse ...@@ -15,7 +15,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Pick and lift state machine for lift environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Keyboard teleoperation for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.")
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Zero agent for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from RL-Games.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
...@@ -14,7 +14,7 @@ import os ...@@ -14,7 +14,7 @@ import os
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Train an RL agent with RL-Games.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.") parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).") parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Collect demonstrations for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.")
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Play policy trained using robomimic for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--task", type=str, default=None, help="Name of the task.") parser.add_argument("--task", type=str, default=None, help="Name of the task.")
......
...@@ -13,7 +13,7 @@ import os ...@@ -13,7 +13,7 @@ import os
if __name__ == "__main__": if __name__ == "__main__":
# parse arguments # parse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Merge multiple episodes with single trajectory into one episode.")
parser.add_argument( parser.add_argument(
"--dir", type=str, default=None, help="Path to directory that contains all single episode hdf5 files" "--dir", type=str, default=None, help="Path to directory that contains all single episode hdf5 files"
) )
......
...@@ -25,7 +25,7 @@ def check_group(f, num: int): ...@@ -25,7 +25,7 @@ def check_group(f, num: int):
if __name__ == "__main__": if __name__ == "__main__":
# parse arguments # parse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Check structure of hdf5 file.")
parser.add_argument("file", type=str, default=None, help="The path to HDF5 file to analyze.") parser.add_argument("file", type=str, default=None, help="The path to HDF5 file to analyze.")
args_cli = parser.parse_args() args_cli = parser.parse_args()
......
...@@ -13,7 +13,7 @@ import argparse ...@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from RSL-RL.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
...@@ -14,7 +14,7 @@ import os ...@@ -14,7 +14,7 @@ import os
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Train an RL agent with RSL-RL.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.") parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).") parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
...@@ -14,7 +14,7 @@ import numpy as np ...@@ -14,7 +14,7 @@ import numpy as np
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from Stable-Baselines3.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
...@@ -15,7 +15,7 @@ import os ...@@ -15,7 +15,7 @@ import os
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Train an RL agent with Stable-Baselines3.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.") parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).") parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
...@@ -19,7 +19,7 @@ import os ...@@ -19,7 +19,7 @@ import os
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from skrl.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.") parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.") parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
...@@ -19,7 +19,7 @@ import os ...@@ -19,7 +19,7 @@ import os
from omni.isaac.orbit.app import AppLauncher from omni.isaac.orbit.app import AppLauncher
# add argparse arguments # add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!") parser = argparse.ArgumentParser(description="Train an RL agent with skrl.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.") parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.") parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).") parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
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