We have now released v0.3.0! Please use the latest version for the best experience.

Saving rendered images and 3D re-projection

Saving rendered images and 3D re-projection#

This guide accompanied with the run_usd_camera.py script in the orbit/source/standalone/tutorials/04_sensors directory.

Code for run_usd_camera.py
  1# Copyright (c) 2022-2024, The ORBIT Project Developers.
  2# All rights reserved.
  3#
  4# SPDX-License-Identifier: BSD-3-Clause
  5
  6"""
  7This script shows how to use the camera sensor from the Orbit framework.
  8
  9The camera sensor is created and interfaced through the Omniverse Replicator API. However, instead of using
 10the simulator or OpenGL convention for the camera, we use the robotics or ROS convention.
 11
 12.. code-block:: bash
 13
 14    # Usage with GUI
 15    ./orbit.sh -p source/standalone/tutorials/04_sensors/run_usd_camera.py
 16
 17    # Usage with headless
 18    ./orbit.sh -p source/standalone/tutorials/04_sensors/run_usd_camera.py --headless --offscreen_render
 19
 20"""
 21
 22"""Launch Isaac Sim Simulator first."""
 23
 24import argparse
 25
 26from omni.isaac.orbit.app import AppLauncher
 27
 28# add argparse arguments
 29parser = argparse.ArgumentParser(description="This script demonstrates how to use the camera sensor.")
 30parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU device for camera output.")
 31parser.add_argument(
 32    "--draw",
 33    action="store_true",
 34    default=False,
 35    help="Draw the pointcloud from camera at index specified by ``--camera_id``.",
 36)
 37parser.add_argument(
 38    "--save",
 39    action="store_true",
 40    default=False,
 41    help="Save the data from camera at index specified by ``--camera_id``.",
 42)
 43parser.add_argument(
 44    "--camera_id",
 45    type=int,
 46    choices={0, 1},
 47    default=0,
 48    help=(
 49        "The camera ID to use for displaying points or saving the camera data. Default is 0."
 50        " The viewport will always initialize with the perspective of camera 0."
 51    ),
 52)
 53# append AppLauncher cli args
 54AppLauncher.add_app_launcher_args(parser)
 55# parse the arguments
 56args_cli = parser.parse_args()
 57# launch omniverse app
 58app_launcher = AppLauncher(args_cli)
 59simulation_app = app_launcher.app
 60
 61"""Rest everything follows."""
 62
 63import numpy as np
 64import os
 65import random
 66import torch
 67
 68import omni.isaac.core.utils.prims as prim_utils
 69import omni.replicator.core as rep
 70
 71import omni.isaac.orbit.sim as sim_utils
 72from omni.isaac.orbit.assets import RigidObject, RigidObjectCfg
 73from omni.isaac.orbit.markers import VisualizationMarkers
 74from omni.isaac.orbit.markers.config import RAY_CASTER_MARKER_CFG
 75from omni.isaac.orbit.sensors.camera import Camera, CameraCfg
 76from omni.isaac.orbit.sensors.camera.utils import create_pointcloud_from_depth
 77from omni.isaac.orbit.utils import convert_dict_to_backend
 78
 79
 80def define_sensor() -> Camera:
 81    """Defines the camera sensor to add to the scene."""
 82    # Setup camera sensor
 83    # In contrast to the ray-cast camera, we spawn the prim at these locations.
 84    # This means the camera sensor will be attached to these prims.
 85    prim_utils.create_prim("/World/Origin_00", "Xform")
 86    prim_utils.create_prim("/World/Origin_01", "Xform")
 87    camera_cfg = CameraCfg(
 88        prim_path="/World/Origin_.*/CameraSensor",
 89        update_period=0,
 90        height=480,
 91        width=640,
 92        data_types=[
 93            "rgb",
 94            "distance_to_image_plane",
 95            "normals",
 96            "semantic_segmentation",
 97            "instance_segmentation_fast",
 98            "instance_id_segmentation_fast",
 99        ],
100        colorize_semantic_segmentation=True,
101        colorize_instance_id_segmentation=True,
102        colorize_instance_segmentation=True,
103        spawn=sim_utils.PinholeCameraCfg(
104            focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
105        ),
106    )
107    # Create camera
108    camera = Camera(cfg=camera_cfg)
109
110    return camera
111
112
113def design_scene() -> dict:
114    """Design the scene."""
115    # Populate scene
116    # -- Ground-plane
117    cfg = sim_utils.GroundPlaneCfg()
118    cfg.func("/World/defaultGroundPlane", cfg)
119    # -- Lights
120    cfg = sim_utils.DistantLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
121    cfg.func("/World/Light", cfg)
122
123    # Create a dictionary for the scene entities
124    scene_entities = {}
125
126    # Xform to hold objects
127    prim_utils.create_prim("/World/Objects", "Xform")
128    # Random objects
129    for i in range(8):
130        # sample random position
131        position = np.random.rand(3) - np.asarray([0.05, 0.05, -1.0])
132        position *= np.asarray([1.5, 1.5, 0.5])
133        # sample random color
134        color = (random.random(), random.random(), random.random())
135        # choose random prim type
136        prim_type = random.choice(["Cube", "Cone", "Cylinder"])
137        common_properties = {
138            "rigid_props": sim_utils.RigidBodyPropertiesCfg(),
139            "mass_props": sim_utils.MassPropertiesCfg(mass=5.0),
140            "collision_props": sim_utils.CollisionPropertiesCfg(),
141            "visual_material": sim_utils.PreviewSurfaceCfg(diffuse_color=color, metallic=0.5),
142            "semantic_tags": [("class", prim_type)],
143        }
144        if prim_type == "Cube":
145            shape_cfg = sim_utils.CuboidCfg(size=(0.25, 0.25, 0.25), **common_properties)
146        elif prim_type == "Cone":
147            shape_cfg = sim_utils.ConeCfg(radius=0.1, height=0.25, **common_properties)
148        elif prim_type == "Cylinder":
149            shape_cfg = sim_utils.CylinderCfg(radius=0.25, height=0.25, **common_properties)
150        # Rigid Object
151        obj_cfg = RigidObjectCfg(
152            prim_path=f"/World/Objects/Obj_{i:02d}",
153            spawn=shape_cfg,
154            init_state=RigidObjectCfg.InitialStateCfg(pos=position),
155        )
156        scene_entities[f"rigid_object{i}"] = RigidObject(cfg=obj_cfg)
157
158    # Sensors
159    camera = define_sensor()
160
161    # return the scene information
162    scene_entities["camera"] = camera
163    return scene_entities
164
165
166def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict):
167    """Run the simulator."""
168    # extract entities for simplified notation
169    camera: Camera = scene_entities["camera"]
170
171    # Create replicator writer
172    output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera")
173    rep_writer = rep.BasicWriter(
174        output_dir=output_dir,
175        frame_padding=0,
176        colorize_instance_id_segmentation=camera.cfg.colorize_instance_id_segmentation,
177        colorize_instance_segmentation=camera.cfg.colorize_instance_segmentation,
178        colorize_semantic_segmentation=camera.cfg.colorize_semantic_segmentation,
179    )
180
181    # Camera positions, targets, orientations
182    camera_positions = torch.tensor([[2.5, 2.5, 2.5], [-2.5, -2.5, 2.5]], device=sim.device)
183    camera_targets = torch.tensor([[0.0, 0.0, 0.0], [0.0, 0.0, 0.0]], device=sim.device)
184    # These orientations are in ROS-convention, and will position the cameras to view the origin
185    camera_orientations = torch.tensor(  # noqa: F841
186        [[-0.1759, 0.3399, 0.8205, -0.4247], [-0.4247, 0.8205, -0.3399, 0.1759]], device=sim.device
187    )
188
189    # Set pose: There are two ways to set the pose of the camera.
190    # -- Option-1: Set pose using view
191    camera.set_world_poses_from_view(camera_positions, camera_targets)
192    # -- Option-2: Set pose using ROS
193    # camera.set_world_poses(camera_positions, camera_orientations, convention="ros")
194
195    # Index of the camera to use for visualization and saving
196    camera_index = args_cli.camera_id
197
198    # Create the markers for the --draw option outside of is_running() loop
199    if sim.has_gui() and args_cli.draw:
200        cfg = RAY_CASTER_MARKER_CFG.replace(prim_path="/Visuals/CameraPointCloud")
201        cfg.markers["hit"].radius = 0.002
202        pc_markers = VisualizationMarkers(cfg)
203
204    # Simulate physics
205    while simulation_app.is_running():
206        # Step simulation
207        sim.step()
208        # Update camera data
209        camera.update(dt=sim.get_physics_dt())
210
211        # Print camera info
212        print(camera)
213        if "rgb" in camera.data.output.keys():
214            print("Received shape of rgb image        : ", camera.data.output["rgb"].shape)
215        if "distance_to_image_plane" in camera.data.output.keys():
216            print("Received shape of depth image      : ", camera.data.output["distance_to_image_plane"].shape)
217        if "normals" in camera.data.output.keys():
218            print("Received shape of normals          : ", camera.data.output["normals"].shape)
219        if "semantic_segmentation" in camera.data.output.keys():
220            print("Received shape of semantic segm.   : ", camera.data.output["semantic_segmentation"].shape)
221        if "instance_segmentation_fast" in camera.data.output.keys():
222            print("Received shape of instance segm.   : ", camera.data.output["instance_segmentation_fast"].shape)
223        if "instance_id_segmentation_fast" in camera.data.output.keys():
224            print("Received shape of instance id segm.: ", camera.data.output["instance_id_segmentation_fast"].shape)
225        print("-------------------------------")
226
227        # Extract camera data
228        if args_cli.save:
229            # Save images from camera at camera_index
230            # note: BasicWriter only supports saving data in numpy format, so we need to convert the data to numpy.
231            # tensordict allows easy indexing of tensors in the dictionary
232            single_cam_data = convert_dict_to_backend(camera.data.output[camera_index], backend="numpy")
233
234            # Extract the other information
235            single_cam_info = camera.data.info[camera_index]
236
237            # Pack data back into replicator format to save them using its writer
238            rep_output = dict()
239            for key, data, info in zip(single_cam_data.keys(), single_cam_data.values(), single_cam_info.values()):
240                if info is not None:
241                    rep_output[key] = {"data": data, "info": info}
242                else:
243                    rep_output[key] = data
244            # Save images
245            # Note: We need to provide On-time data for Replicator to save the images.
246            rep_output["trigger_outputs"] = {"on_time": camera.frame[camera_index]}
247            rep_writer.write(rep_output)
248
249        # Draw pointcloud if there is a GUI and --draw has been passed
250        if sim.has_gui() and args_cli.draw and "distance_to_image_plane" in camera.data.output.keys():
251            # Derive pointcloud from camera at camera_index
252            pointcloud = create_pointcloud_from_depth(
253                intrinsic_matrix=camera.data.intrinsic_matrices[camera_index],
254                depth=camera.data.output[camera_index]["distance_to_image_plane"],
255                position=camera.data.pos_w[camera_index],
256                orientation=camera.data.quat_w_ros[camera_index],
257                device=sim.device,
258            )
259
260            # In the first few steps, things are still being instanced and Camera.data
261            # can be empty. If we attempt to visualize an empty pointcloud it will crash
262            # the sim, so we check that the pointcloud is not empty.
263            if pointcloud.size()[0] > 0:
264                pc_markers.visualize(translations=pointcloud)
265
266
267def main():
268    """Main function."""
269    # Load simulation context
270    sim_cfg = sim_utils.SimulationCfg(device="cpu" if args_cli.cpu else "cuda")
271    sim = sim_utils.SimulationContext(sim_cfg)
272    # Set main camera
273    sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
274    # design the scene
275    scene_entities = design_scene()
276    # Play simulator
277    sim.reset()
278    # Now we are ready!
279    print("[INFO]: Setup complete...")
280    # Run simulator
281    run_simulator(sim, scene_entities)
282
283
284if __name__ == "__main__":
285    # run the main function
286    main()
287    # close sim app
288    simulation_app.close()

Saving using Replicator Basic Writer#

To save camera outputs, we use the basic write class from Omniverse Replicator. This class allows us to save the images in a numpy format. For more information on the basic writer, please check the documentation.

    rep_writer = rep.BasicWriter(
        output_dir=output_dir,
        frame_padding=0,
        colorize_instance_id_segmentation=camera.cfg.colorize_instance_id_segmentation,
        colorize_instance_segmentation=camera.cfg.colorize_instance_segmentation,
        colorize_semantic_segmentation=camera.cfg.colorize_semantic_segmentation,
    )

While stepping the simulator, the images can be saved to the defined folder. Since the BasicWriter only supports saving data using NumPy format, we first need to convert the PyTorch sensors to NumPy arrays before packing them in a dictionary.

            # Save images from camera at camera_index
            # note: BasicWriter only supports saving data in numpy format, so we need to convert the data to numpy.
            # tensordict allows easy indexing of tensors in the dictionary
            single_cam_data = convert_dict_to_backend(camera.data.output[camera_index], backend="numpy")

            # Extract the other information
            single_cam_info = camera.data.info[camera_index]

After this step, we can save the images using the BasicWriter.

            # Pack data back into replicator format to save them using its writer
            rep_output = dict()
            for key, data, info in zip(single_cam_data.keys(), single_cam_data.values(), single_cam_info.values()):
                if info is not None:
                    rep_output[key] = {"data": data, "info": info}
                else:
                    rep_output[key] = data
            # Save images
            # Note: We need to provide On-time data for Replicator to save the images.
            rep_output["trigger_outputs"] = {"on_time": camera.frame[camera_index]}
            rep_writer.write(rep_output)

Projection into 3D Space#

We include utilities to project the depth image into 3D Space. The re-projection operations are done using PyTorch operations which allows faster computation.

from omni.isaac.orbit.utils.math import transform_points, unproject_depth

# Pointcloud in world frame
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.pos_w, camera.data.quat_w_ros)

Alternately, we can use the omni.isaac.orbit.sensors.camera.utils.create_pointcloud_from_depth() function to create a point cloud from the depth image and transform it to the world frame.

            # Derive pointcloud from camera at camera_index
            pointcloud = create_pointcloud_from_depth(
                intrinsic_matrix=camera.data.intrinsic_matrices[camera_index],
                depth=camera.data.output[camera_index]["distance_to_image_plane"],
                position=camera.data.pos_w[camera_index],
                orientation=camera.data.quat_w_ros[camera_index],
                device=sim.device,
            )

The resulting point cloud can be visualized using the omni.isaac.debug_draw extension from Isaac Sim. This makes it easy to visualize the point cloud in the 3D space.

            # In the first few steps, things are still being instanced and Camera.data
            # can be empty. If we attempt to visualize an empty pointcloud it will crash
            # the sim, so we check that the pointcloud is not empty.
            if pointcloud.size()[0] > 0:
                pc_markers.visualize(translations=pointcloud)

Executing the script#

To run the accompanying script, execute the following command:

# Usage with saving and drawing
./orbit.sh -p source/standalone/tutorials/04_sensors/run_usd_camera.py --save --draw

# Usage with saving only in headless mode
./orbit.sh -p source/standalone/tutorials/04_sensors/run_usd_camera.py --save --headless --offscreen_render

The simulation should start, and you can observe different objects falling down. An output folder will be created in the orbit/source/standalone/tutorials/04_sensors directory, where the images will be saved. Additionally, you should see the point cloud in the 3D space drawn on the viewport.

To stop the simulation, close the window, press the STOP button in the UI, or use Ctrl+C in the terminal.