@@ -46,6 +46,7 @@ class State:
46
46
override_simulation_time = False
47
47
imu_sensor_interface = None
48
48
imu_prim_path = ""
49
+ imu_prim = None
49
50
invalid_images_count = 0
50
51
pass
51
52
@@ -153,15 +154,18 @@ def compute(db) -> bool:
153
154
154
155
if (db .internal_state .annotator_left is None ):
155
156
render_product_path_left = SlCameraStreamer .get_render_product_path (left_cam_path )
156
- db .internal_state .annotator_left = rep .AnnotatorRegistry .get_annotator ("rgb" )
157
+ db .internal_state .annotator_left = rep .AnnotatorRegistry .get_annotator ("rgb" , device = "cuda" , do_array_copy = False )
157
158
db .internal_state .annotator_left .attach ([render_product_path_left ])
158
159
159
160
if (db .internal_state .annotator_right is None ):
160
161
render_product_path_right = SlCameraStreamer .get_render_product_path (right_cam_path )
161
- db .internal_state .annotator_right = rep .AnnotatorRegistry .get_annotator ("rgb" )
162
+ db .internal_state .annotator_right = rep .AnnotatorRegistry .get_annotator ("rgb" , device = "cuda" , do_array_copy = False )
162
163
db .internal_state .annotator_right .attach ([render_product_path_right ])
163
164
164
165
db .internal_state .imu_prim_path = db .inputs .camera_prim [0 ].pathString + IMU_PRIM_PATH
166
+ db .internal_state .imu_prim = XFormPrim (prim_path = db .internal_state .imu_prim_path )
167
+
168
+ carb .settings .get_settings ().set ("/omni/replicator/captureOnPlay" , False )
165
169
166
170
# Setup streamer parameters
167
171
db .internal_state .pyzed_streamer = ZEDSimStreamer ()
@@ -202,7 +206,7 @@ def compute(db) -> bool:
202
206
carb .log_warn (f"{ db .internal_state .camera_prim_name } - Left camera retrieved unexpected "
203
207
"data shape, skipping frame." )
204
208
return False # no need to continue compute
205
-
209
+
206
210
right , res = SlCameraStreamer .get_image_data (db .internal_state .annotator_right )
207
211
if res == False :
208
212
db .internal_state .invalid_images_count += 1
@@ -229,8 +233,8 @@ def compute(db) -> bool:
229
233
# their IMUand still have access to the image functionality without issues in Isaac Sim
230
234
lin_acc_x , lin_acc_y , lin_acc_z = 0 , 0 , 0
231
235
orientation = [0 ]* 4
232
- if is_prim_path_valid (db .internal_state .imu_prim_path ) == True :
233
- imu_prim = XFormPrim ( prim_path = db .internal_state .imu_prim_path )
236
+ if is_prim_path_valid (db .internal_state .imu_prim_path ) == True and db . internal_state . imu_prim is not None :
237
+ imu_prim = db .internal_state .imu_prim
234
238
temp_orientation = imu_prim .get_world_pose ()[1 ]
235
239
swp = copy .deepcopy (temp_orientation )
236
240
orientation = [swp [0 ], - swp [1 ], - swp [3 ], - swp [2 ]]
@@ -244,12 +248,15 @@ def compute(db) -> bool:
244
248
lin_acc_x = imu_reading .lin_acc_x
245
249
lin_acc_y = imu_reading .lin_acc_y
246
250
lin_acc_z = imu_reading .lin_acc_z
247
-
251
+
248
252
# stream data
249
253
if not (left is None ) and not (right is None ):
254
+ # Copy GPU image data to CPU and convert to bytes
255
+ left_bytes = left .numpy ().tobytes ()
256
+ right_bytes = right .numpy ().tobytes ()
250
257
res = db .internal_state .pyzed_streamer .stream (
251
- left . tobytes () ,
252
- right . tobytes () ,
258
+ left_bytes ,
259
+ right_bytes ,
253
260
ts ,
254
261
orientation [0 ],
255
262
orientation [1 ],
@@ -266,7 +273,6 @@ def compute(db) -> bool:
266
273
else :
267
274
carb .log_verbose (f"Streamed at { ts } 2 rgb images and orientation: { orientation } " )
268
275
db .internal_state .last_timestamp = current_time
269
-
270
276
271
277
except Exception as error :
272
278
# If anything causes your compute to fail report the error and return False
@@ -278,25 +284,28 @@ def compute(db) -> bool:
278
284
279
285
@staticmethod
280
286
def release (node ):
281
- carb .log_verbose ("Releasing resources" )
287
+ carb .log_verbose ("Releasing resources" )
282
288
try :
283
289
state = SlCameraStreamerDatabase .per_node_internal_state (node )
284
290
if state is not None :
285
291
# disabling this could fix the render product issue (return empty arrays) when the scene reloads
286
292
# but could also create issues when attaching cameras to render products
287
293
if state .annotator_left :
288
- state .annotator_left .detach ([ state . render_product_left ] )
294
+ state .annotator_left .detach ()
289
295
if state .render_product_left is not None :
296
+ state .render_product_left .hydra_texture .set_updates_enabled (False )
290
297
state .render_product_left .destroy ()
291
298
if state .annotator_right :
292
- state .annotator_right .detach ([ state . render_product_right ] )
299
+ state .annotator_right .detach ()
293
300
if state .render_product_right is not None :
301
+ state .render_product_right .hydra_texture .set_updates_enabled (False )
294
302
state .render_product_right .destroy ()
295
-
303
+
296
304
if state .pyzed_streamer :
297
305
state .pyzed_streamer .close ()
298
306
# remove the streamer object when no longer needed
299
307
del state .pyzed_streamer
308
+
300
309
_sensor .release_imu_sensor_interface (state .imu_sensor_interface )
301
310
state .initialized = False
302
311
0 commit comments