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 IsaacLab/scripts/tutorials/04_sensors directory.

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

Saving using Replicator Basic Writer#

Note

The BasicWriter is part of the Omniverse Replicator ecosystem and is specific to the default Isaac RTX renderer backend. Other renderer backends may require different save workflows.

Note

The colorize_* arguments below are set on renderer_cfg (an IsaacRtxRendererCfg); the same-named fields on CameraCfg are deprecated.

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.renderer_cfg.colorize_instance_id_segmentation,
        colorize_instance_segmentation=camera.cfg.renderer_cfg.colorize_instance_segmentation,
        colorize_semantic_segmentation=camera.cfg.renderer_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 and writing with the BasicWriter.

            # 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.
            single_cam_data = convert_dict_to_backend(
                {k: v[camera_index] for k, v in camera.data.output.items()}, backend="numpy"
            )

            # Pack data back into replicator format to save them using its writer
            rep_output = {"annotators": {}}
            for key, data in single_cam_data.items():
                info = camera.data.info.get(key)
                if info is not None:
                    rep_output["annotators"][key] = {"render_product": {"data": data, **info}}
                else:
                    rep_output["annotators"][key] = {"render_product": {"data": 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 isaaclab.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 isaaclab.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["distance_to_image_plane"][camera_index],
                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 isaacsim.util.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
./isaaclab.sh -p scripts/tutorials/04_sensors/run_usd_camera.py --save --draw --enable_cameras

# Usage with saving only in headless mode
./isaaclab.sh -p scripts/tutorials/04_sensors/run_usd_camera.py --save --headless --enable_cameras

The simulation should start, and you can observe different objects falling down. An output folder will be created in the IsaacLab/scripts/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, or use Ctrl+C in the terminal.