Unverified Commit 0154535e authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Adds an example showcasing different camera types (#565)

# Description

This MR fixes some of the docstrings related to the tile-rendering
camera. Additionally, it adds a demo script showcasing the images
obtained through the different camera implementations in IsaacLab.

## 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
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have run all the tests with `./isaaclab.sh --test` and they pass
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent 3ef7e678
......@@ -18,6 +18,8 @@
Camera
CameraData
CameraCfg
TiledCamera
TiledCameraCfg
ContactSensor
ContactSensorData
ContactSensorCfg
......@@ -29,8 +31,6 @@
RayCasterCfg
RayCasterCamera
RayCasterCameraCfg
TiledCamera
TiledCameraCfg
Sensor Base
-----------
......@@ -61,6 +61,20 @@ USD Camera
:show-inheritance:
:exclude-members: __init__, class_type
Tile-Rendered USD Camera
------------------------
.. autoclass:: TiledCamera
:members:
:inherited-members:
:show-inheritance:
.. autoclass:: TiledCameraCfg
:members:
:inherited-members:
:show-inheritance:
:exclude-members: __init__, class_type
Contact Sensor
--------------
......@@ -80,7 +94,6 @@ Contact Sensor
:show-inheritance:
:exclude-members: __init__, class_type
Frame Transformer
-----------------
......@@ -137,17 +150,3 @@ Ray-Cast Camera
:inherited-members:
:show-inheritance:
:exclude-members: __init__, class_type
Tiled Rendering
---------------
.. autoclass:: TiledCamera
:members:
:inherited-members:
:show-inheritance:
.. autoclass:: TiledCameraCfg
:members:
:inherited-members:
:show-inheritance:
:exclude-members: __init__, class_type
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.18.1"
version = "0.18.2"
# Description
title = "Isaac Lab framework for Robot Learning"
......
Changelog
---------
0.18.2 (2024-06-25)
~~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Moved the configuration for tile-rendered camera into its own file named ``tiled_camera_cfg.py``.
This makes it easier to follow where the configuration is located and how it is related to the class.
0.18.1 (2024-06-25)
~~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Ensured that a parity between class and its configuration class is explicitly visible in the :class:`omni.isaac.lab.envs`
module. This makes it easier to follow where definitions are located and how they are related. This should not be
a breaking change as the classes are still accessible through the same module.
* Ensured that a parity between class and its configuration class is explicitly visible in the
:mod:`omni.isaac.lab.envs` module. This makes it easier to follow where definitions are located and how
they are related. This should not be a breaking change as the classes are still accessible through the same module.
0.18.0 (2024-06-13)
......
......@@ -6,7 +6,8 @@
"""Sub-module for camera wrapper around USD camera prim."""
from .camera import Camera
from .camera_cfg import CameraCfg, TiledCameraCfg
from .camera_cfg import CameraCfg
from .camera_data import CameraData
from .tiled_camera import TiledCamera
from .tiled_camera_cfg import TiledCameraCfg
from .utils import * # noqa: F401, F403
......@@ -11,7 +11,6 @@ from omni.isaac.lab.utils import configclass
from ..sensor_base_cfg import SensorBaseCfg
from .camera import Camera
from .tiled_camera import TiledCamera
@configclass
......@@ -107,64 +106,3 @@ class CameraCfg(SensorBaseCfg):
If True, instance segmentation is converted to an image where instance IDs are mapped to colors.
and returned as a ``uint8`` 4-channel array. If False, the output is returned as a ``int32`` array.
"""
@configclass
class TiledCameraCfg(SensorBaseCfg):
"""Configuration for a tiled rendering camera sensor."""
@configclass
class OffsetCfg:
"""The offset pose of the sensor's frame from the sensor's parent frame."""
pos: tuple[float, float, float] = (0.0, 0.0, 0.0)
"""Translation w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0)."""
rot: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0)
"""Quaternion rotation (w, x, y, z) w.r.t. the parent frame. Defaults to (1.0, 0.0, 0.0, 0.0)."""
convention: Literal["opengl", "ros", "world"] = "ros"
"""The convention in which the frame offset is applied. Defaults to "ros".
- ``"opengl"`` - forward axis: ``-Z`` - up axis: ``+Y`` - Offset is applied in the OpenGL (Usd.Camera) convention.
- ``"ros"`` - forward axis: ``+Z`` - up axis: ``-Y`` - Offset is applied in the ROS convention.
- ``"world"`` - forward axis: ``+X`` - up axis: ``+Z`` - Offset is applied in the World Frame convention.
"""
class_type: type = TiledCamera
offset: OffsetCfg = OffsetCfg()
"""The offset pose of the sensor's frame from the sensor's parent frame. Defaults to identity.
Note:
The parent frame is the frame the sensor attaches to. For example, the parent frame of a
camera at path ``/World/envs/env_0/Robot/Camera`` is ``/World/envs/env_0/Robot``.
"""
spawn: PinholeCameraCfg | FisheyeCameraCfg | None = MISSING
"""Spawn configuration for the asset.
If None, then the prim is not spawned by the asset. Instead, it is assumed that the
asset is already present in the scene.
"""
data_types: list[str] = ["rgb"]
"""List of sensor names/types to enable for the camera. Defaults to ["rgb"].
Please refer to the :class:`Camera` class for a list of available data types.
"""
width: int = MISSING
"""Width of the image in pixels."""
height: int = MISSING
"""Height of the image in pixels."""
return_latest_camera_pose: bool = False
"""Whether to return the latest camera pose when fetching the camera's data. Defaults to False.
If True, the latest camera pose is returned in the camera's data which will slow down performance
due to the use of :class:`XformPrimView`.
If False, the pose of the camera during initialization is returned.
"""
......@@ -27,17 +27,27 @@ if TYPE_CHECKING:
class TiledCamera(Camera):
r"""The tiled rendering camera sensor for acquiring RGB and depth data.
r"""The tiled rendering based camera sensor for acquiring RGB and depth data.
This class wraps over the `UsdGeom Camera`_ for providing a consistent API for acquiring visual data.
It ensures that the camera follows the ROS convention for the coordinate system.
This class inherits from the :class:`Camera` class but uses the tiled-rendering API from Replicator to acquire
the visual data. Tiled-rendering concatenates the rendered images from multiple cameras into a single image.
This allows for rendering multiple cameras in parallel and is useful for rendering large scenes with multiple
cameras efficiently.
The following sensor types are supported:
- ``"rgb"``: A rendered color image.
- ``"depth"``: An image containing the distance to camera optical center.
.. _USDGeom Camera: https://graphics.pixar.com/usd/docs/api/class_usd_geom_camera.html
.. versionadded:: Isaac Sim 4.0
This feature is available starting from Isaac Sim 4.0. Before this version, the tiled rendering APIs
were not available.
.. attention::
Please note that the fidelity of RGB images may be lower than the standard camera sensor due to the
tiled rendering process. Various ray tracing effects such as reflections, refractions, and shadows may not be
accurately captured in the RGB images. We are currently working on improving the fidelity of the RGB images.
"""
......@@ -61,7 +71,9 @@ class TiledCamera(Camera):
def __del__(self):
"""Unsubscribes from callbacks and detach from the replicator registry."""
# unsubscribe from callbacks
SensorBase.__del__(self)
# detach from the replicator registry
self._annotator.detach(self.render_product_paths)
def __str__(self) -> str:
......@@ -86,9 +98,10 @@ class TiledCamera(Camera):
)
# reset the timestamps
SensorBase.reset(self, env_ids)
# resolve None
if env_ids is None:
env_ids = self._ALL_INDICES
# Reset the frame count
env_ids = slice(None)
# reset the frame count
self._frame[env_ids] = 0
"""
......@@ -142,37 +155,38 @@ class TiledCamera(Camera):
sensor_prim = UsdGeom.Camera(cam_prim)
self._sensor_prims.append(sensor_prim)
# start the orchestrator (if not already started)
rep.orchestrator._orchestrator._is_started = True
sensor = rep.create.tiled_sensor(
# Create a tiled sensor from the camera prims
rep_sensor = rep.create.tiled_sensor(
cameras=self._view.prim_paths,
camera_resolution=[self.image_shape[1], self.image_shape[0]],
tiled_resolution=self._tiled_image_shape(),
output_types=self.cfg.data_types,
)
render_prod_path = rep.create.render_product(camera=sensor, resolution=self._tiled_image_shape())
# Get render product
render_prod_path = rep.create.render_product(camera=rep_sensor, resolution=self._tiled_image_shape())
if not isinstance(render_prod_path, str):
render_prod_path = render_prod_path.path
self._render_product_paths = [render_prod_path]
# Attach the annotator
self._annotator = rep.AnnotatorRegistry.get_annotator("RtxSensorGpu", device=self.device, do_array_copy=False)
self._annotator.attach(self._render_product_paths)
# Create internal buffers
self._create_buffers()
def _create_annotator_data(self):
raise RuntimeError("Annotator data is not available for the tiled camera sensor.")
def _process_annotator_output(self, name: str, output: Any) -> tuple[torch.tensor, dict | None]:
raise RuntimeError("Annotator data is not available for the tiled camera sensor.")
def _update_buffers_impl(self, env_ids: Sequence[int]):
# Increment frame count
self._frame[env_ids] += 1
# Extract the flattened image buffer
tiled_data_buffer = self._annotator.get_data()
if isinstance(tiled_data_buffer, np.ndarray):
tiled_data_buffer = wp.array(tiled_data_buffer, device=self.device)
else:
tiled_data_buffer = tiled_data_buffer.to(device=self.device)
# The offset is needed when the buffer contains rgb and depth (the buffer has RGB data first and then depth)
offset = self._data.output["rgb"].numel() if "rgb" in self.cfg.data_types else 0
for data_type in self.cfg.data_types:
......@@ -193,17 +207,6 @@ class TiledCamera(Camera):
Private Helpers
"""
def _tiled_image_shape(self) -> tuple[int, int]:
"""A tuple containing the dimension of the tiled image."""
cols, rows = self._tiling_grid_shape()
return (self.cfg.width * cols, self.cfg.height * rows)
def _tiling_grid_shape(self) -> tuple[int, int]:
"""A tuple containing the tiling grid dimension."""
cols = round(math.sqrt(self._view.count))
rows = math.ceil(self._view.count / cols)
return (cols, rows)
def _check_supported_data_types(self, cfg: TiledCameraCfg):
"""Checks if the data types are supported by the camera."""
if not set(cfg.data_types).issubset(TiledCamera.SUPPORTED_TYPES):
......@@ -235,6 +238,25 @@ class TiledCamera(Camera):
).contiguous()
self._data.output = TensorDict(data_dict, batch_size=self._view.count, device=self.device)
def _tiled_image_shape(self) -> tuple[int, int]:
"""Returns a tuple containing the dimension of the tiled image."""
cols, rows = self._tiling_grid_shape()
return (self.cfg.width * cols, self.cfg.height * rows)
def _tiling_grid_shape(self) -> tuple[int, int]:
"""Returns a tuple containing the tiling grid dimension."""
cols = round(math.sqrt(self._view.count))
rows = math.ceil(self._view.count / cols)
return (cols, rows)
def _create_annotator_data(self):
# we do not need to create annotator data for the tiled camera sensor
raise RuntimeError("This function should not be called for the tiled camera sensor.")
def _process_annotator_output(self, name: str, output: Any) -> tuple[torch.tensor, dict | None]:
# we do not need to process annotator output for the tiled camera sensor
raise RuntimeError("This function should not be called for the tiled camera sensor.")
"""
Internal simulation callbacks.
"""
......
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from dataclasses import MISSING
from typing import Literal
from omni.isaac.lab.sim import FisheyeCameraCfg, PinholeCameraCfg
from omni.isaac.lab.utils import configclass
from ..sensor_base_cfg import SensorBaseCfg
from .tiled_camera import TiledCamera
@configclass
class TiledCameraCfg(SensorBaseCfg):
"""Configuration for a tiled rendering-based camera sensor."""
@configclass
class OffsetCfg:
"""The offset pose of the sensor's frame from the sensor's parent frame."""
pos: tuple[float, float, float] = (0.0, 0.0, 0.0)
"""Translation w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0)."""
rot: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0)
"""Quaternion rotation (w, x, y, z) w.r.t. the parent frame. Defaults to (1.0, 0.0, 0.0, 0.0)."""
convention: Literal["opengl", "ros", "world"] = "ros"
"""The convention in which the frame offset is applied. Defaults to "ros".
- ``"opengl"`` - forward axis: ``-Z`` - up axis: ``+Y`` - Offset is applied in the OpenGL (Usd.Camera) convention.
- ``"ros"`` - forward axis: ``+Z`` - up axis: ``-Y`` - Offset is applied in the ROS convention.
- ``"world"`` - forward axis: ``+X`` - up axis: ``+Z`` - Offset is applied in the World Frame convention.
"""
class_type: type = TiledCamera
offset: OffsetCfg = OffsetCfg()
"""The offset pose of the sensor's frame from the sensor's parent frame. Defaults to identity.
Note:
The parent frame is the frame the sensor attaches to. For example, the parent frame of a
camera at path ``/World/envs/env_0/Robot/Camera`` is ``/World/envs/env_0/Robot``.
"""
spawn: PinholeCameraCfg | FisheyeCameraCfg | None = MISSING
"""Spawn configuration for the asset.
If None, then the prim is not spawned by the asset. Instead, it is assumed that the
asset is already present in the scene.
"""
data_types: list[str] = ["rgb"]
"""List of sensor names/types to enable for the camera. Defaults to ["rgb"].
Please refer to the :class:`TiledCamera` class for a list of available data types.
"""
width: int = MISSING
"""Width of the image in pixels."""
height: int = MISSING
"""Height of the image in pixels."""
return_latest_camera_pose: bool = False
"""Whether to return the latest camera pose when fetching the camera's data. Defaults to False.
If True, the latest camera pose is returned in the camera's data which will slow down performance
due to the use of :class:`XformPrimView`.
If False, the pose of the camera during initialization is returned.
"""
......@@ -83,25 +83,35 @@ def reshape_tiled_image(
num_tiles_x: int,
offset: int,
):
"""Reshape a tiled image (height*width*num_channels*num_cameras,) to a batch of images (num_cameras, height, width, num_channels).
"""Reshapes a tiled image into a batch of images.
This function reshapes the input tiled image buffer into a batch of images. The input image buffer
is assumed to be tiled in the x and y directions. The output image is a batch of images with the
specified height, width, and number of channels.
Args:
tiled_image_buffer: The input image buffer. Shape is (height*width*num_channels*num_cameras,).
tiled_image_buffer: The input image buffer. Shape is (height * width * num_channels * num_cameras,).
batched_image: The output image. Shape is (num_cameras, height, width, num_channels).
image_width: The width of the image.
image_height: The height of the image.
num_channels: The number of channels in the image.
num_tiles_x: The number of tiles in x direction.
num_tiles_x: The number of tiles in x-direction.
offset: The offset in the image buffer. This is used when multiple image types are concatenated in the buffer.
"""
# get the thread id
camera_id, height_id, width_id = wp.tid()
# resolve the tile indices
tile_x_id = camera_id % num_tiles_x
tile_y_id = camera_id // num_tiles_x
# compute the start index of the pixel in the tiled image buffer
pixel_start = (
offset
+ num_channels * num_tiles_x * image_width * (image_height * tile_y_id + height_id)
+ num_channels * tile_x_id * image_width
+ num_channels * width_id
)
# copy the pixel values into the batched image
for i in range(num_channels):
batched_image[camera_id, height_id, width_id, i] = tiled_image_buffer[pixel_start + i]
......@@ -4,7 +4,12 @@
# SPDX-License-Identifier: BSD-3-Clause
"""
This script demonstrates how to simulate a bipedal robot.
This script demonstrates how to simulate bipedal robots.
.. code-block:: bash
# Usage
./isaaclab.sh -p source/standalone/demos/bipeds.py
"""
......@@ -16,7 +21,7 @@ import torch
from omni.isaac.lab.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="This script demonstrates how to simulate a bipedal robot.")
parser = argparse.ArgumentParser(description="This script demonstrates how to simulate bipedal robots.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
......
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script demonstrates the different camera sensors that can be attached to a robot.
.. code-block:: bash
# Usage
./isaaclab.sh -p source/standalone/demos/cameras.py
# Usage in headless mode
./isaaclab.sh -p source/standalone/demos/cameras.py --headless --enable_cameras
"""
"""Launch Isaac Sim Simulator first."""
import argparse
from omni.isaac.lab.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="This script demonstrates the different camera sensor implementations.")
parser.add_argument("--num_envs", type=int, default=4, help="Number of environments to spawn.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()
# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app
"""Rest everything follows."""
import matplotlib.pyplot as plt
import numpy as np
import os
import torch
import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.lab.scene import InteractiveScene, InteractiveSceneCfg
from omni.isaac.lab.sensors import CameraCfg, RayCasterCameraCfg, TiledCameraCfg
from omni.isaac.lab.sensors.ray_caster import patterns
from omni.isaac.lab.terrains import TerrainImporterCfg
from omni.isaac.lab.utils import configclass
##
# Pre-defined configs
##
from omni.isaac.lab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort:skip
from omni.isaac.lab_assets.anymal import ANYMAL_C_CFG # isort: skip
@configclass
class SensorsSceneCfg(InteractiveSceneCfg):
"""Design the scene with sensors on the robot."""
# ground plane
ground = TerrainImporterCfg(
num_envs=2048,
env_spacing=3.0,
prim_path="/World/ground",
max_init_terrain_level=None,
terrain_type="generator",
terrain_generator=ROUGH_TERRAINS_CFG.replace(color_scheme="random"),
visual_material=None,
debug_vis=False,
)
# lights
dome_light = AssetBaseCfg(
prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=2000.0, color=(0.75, 0.75, 0.75))
)
# robot
robot: ArticulationCfg = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
# sensors
camera = CameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/base/front_cam",
update_period=0.1,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane"],
spawn=sim_utils.PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
),
offset=CameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
)
tiled_camera = TiledCameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/base/front_cam",
update_period=0.1,
height=480,
width=640,
data_types=["rgb", "depth"],
spawn=None, # the camera is already spawned in the scene
offset=TiledCameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
)
raycast_camera = RayCasterCameraCfg(
prim_path="{ENV_REGEX_NS}/Robot/base",
mesh_prim_paths=["/World/ground"],
update_period=0.1,
offset=RayCasterCameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"),
data_types=["distance_to_image_plane", "normals"],
pattern_cfg=patterns.PinholeCameraPatternCfg(
focal_length=24.0,
horizontal_aperture=20.955,
height=480,
width=640,
),
)
def save_images_grid(
images: list[torch.Tensor],
cmap: str | None = None,
nrow: int = 1,
subtitles: list[str] | None = None,
title: str | None = None,
filename: str | None = None,
):
"""Save images in a grid with optional subtitles and title.
Args:
images: A list of images to be plotted. Shape of each image should be (H, W, C).
cmap: Colormap to be used for plotting. Defaults to None, in which case the default colormap is used.
nrows: Number of rows in the grid. Defaults to 1.
subtitles: A list of subtitles for each image. Defaults to None, in which case no subtitles are shown.
title: Title of the grid. Defaults to None, in which case no title is shown.
filename: Path to save the figure. Defaults to None, in which case the figure is not saved.
"""
# show images in a grid
n_images = len(images)
ncol = int(np.ceil(n_images / nrow))
fig, axes = plt.subplots(nrow, ncol, figsize=(ncol * 2, nrow * 2))
axes = axes.flatten()
# plot images
for idx, (img, ax) in enumerate(zip(images, axes)):
img = img.detach().cpu().numpy()
ax.imshow(img, cmap=cmap)
ax.axis("off")
if subtitles:
ax.set_title(subtitles[idx])
# remove extra axes if any
for ax in axes[n_images:]:
fig.delaxes(ax)
# set title
if title:
plt.suptitle(title)
# adjust layout to fit the title
plt.tight_layout()
# save the figure
if filename:
os.makedirs(os.path.dirname(filename), exist_ok=True)
plt.savefig(filename)
# close the figure
plt.close()
def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
"""Run the simulator."""
# Define simulation stepping
sim_dt = sim.get_physics_dt()
sim_time = 0.0
count = 0
# Create output directory to save images
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output")
os.makedirs(output_dir, exist_ok=True)
# Simulate physics
while simulation_app.is_running():
# Reset
if count % 500 == 0:
# reset counter
count = 0
# reset the scene entities
# root state
# we offset the root state by the origin since the states are written in simulation world frame
# if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
root_state = scene["robot"].data.default_root_state.clone()
root_state[:, :3] += scene.env_origins
scene["robot"].write_root_state_to_sim(root_state)
# set joint positions with some noise
joint_pos, joint_vel = (
scene["robot"].data.default_joint_pos.clone(),
scene["robot"].data.default_joint_vel.clone(),
)
joint_pos += torch.rand_like(joint_pos) * 0.1
scene["robot"].write_joint_state_to_sim(joint_pos, joint_vel)
# clear internal buffers
scene.reset()
print("[INFO]: Resetting robot state...")
# Apply default actions to the robot
# -- generate actions/commands
targets = scene["robot"].data.default_joint_pos
# -- apply action to the robot
scene["robot"].set_joint_position_target(targets)
# -- write data to sim
scene.write_data_to_sim()
# perform step
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
# update buffers
scene.update(sim_dt)
# print information from the sensors
print("-------------------------------")
print(scene["camera"])
print("Received shape of rgb image: ", scene["camera"].data.output["rgb"].shape)
print("Received shape of depth image: ", scene["camera"].data.output["distance_to_image_plane"].shape)
print("-------------------------------")
print(scene["tiled_camera"])
print("Received shape of rgb image: ", scene["tiled_camera"].data.output["rgb"].shape)
print("Received shape of depth image: ", scene["tiled_camera"].data.output["depth"].shape)
print("-------------------------------")
print(scene["raycast_camera"])
print("Received shape of depth: ", scene["raycast_camera"].data.output["distance_to_image_plane"].shape)
print("Received shape of normals: ", scene["raycast_camera"].data.output["normals"].shape)
# save every 10th image (for visualization purposes only)
# note: saving images will slow down the simulation
if count % 10 == 0:
# compare generated RGB images across different cameras
rgb_images = [scene["camera"].data.output["rgb"][0, ..., :3], scene["tiled_camera"].data.output["rgb"][0]]
save_images_grid(
rgb_images,
subtitles=["Camera", "TiledCamera"],
title="RGB Image: Cam0",
filename=os.path.join(output_dir, "rgb", f"{count:04d}.jpg"),
)
# compare generated Depth images across different cameras
depth_images = [
scene["camera"].data.output["distance_to_image_plane"][0],
scene["tiled_camera"].data.output["depth"][0, ..., 0],
scene["raycast_camera"].data.output["distance_to_image_plane"][0],
]
save_images_grid(
depth_images,
cmap="turbo",
subtitles=["Camera", "TiledCamera", "RaycasterCamera"],
title="Depth Image: Cam0",
filename=os.path.join(output_dir, "depth", f"{count:04d}.jpg"),
)
# save all tiled RGB images
tiled_images = scene["tiled_camera"].data.output["rgb"]
save_images_grid(
tiled_images,
subtitles=[f"Cam{i}" for i in range(tiled_images.shape[0])],
title="Tiled RGB Image",
filename=os.path.join(output_dir, "tiled_rgb", f"{count:04d}.jpg"),
)
# save all camera RGB images
cam_images = scene["camera"].data.output["rgb"][..., :3]
save_images_grid(
cam_images,
subtitles=[f"Cam{i}" for i in range(cam_images.shape[0])],
title="Camera RGB Image",
filename=os.path.join(output_dir, "cam_rgb", f"{count:04d}.jpg"),
)
def main():
"""Main function."""
# Initialize the simulation context
# note: tile rendered cameras don't update the camera poses when using the GPU pipeline and Fabric
sim_cfg = sim_utils.SimulationCfg(dt=0.005, substeps=1, use_fabric=False, device="cpu", use_gpu_pipeline=False)
sim_cfg.physx.use_gpu = False
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
# design scene
scene_cfg = SensorsSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
scene = InteractiveScene(scene_cfg)
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run the simulator
run_simulator(sim, scene)
if __name__ == "__main__":
# run the main function
main()
# close sim app
simulation_app.close()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment