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