@@ -46,6 +46,7 @@ class State:
4646 override_simulation_time = False
4747 imu_sensor_interface = None
4848 imu_prim_path = ""
49+ imu_prim = None
4950 invalid_images_count = 0
5051 pass
5152
@@ -153,15 +154,18 @@ def compute(db) -> bool:
153154
154155 if (db .internal_state .annotator_left is None ):
155156 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 )
157158 db .internal_state .annotator_left .attach ([render_product_path_left ])
158159
159160 if (db .internal_state .annotator_right is None ):
160161 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 )
162163 db .internal_state .annotator_right .attach ([render_product_path_right ])
163164
164165 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 )
165169
166170 # Setup streamer parameters
167171 db .internal_state .pyzed_streamer = ZEDSimStreamer ()
@@ -202,7 +206,7 @@ def compute(db) -> bool:
202206 carb .log_warn (f"{ db .internal_state .camera_prim_name } - Left camera retrieved unexpected "
203207 "data shape, skipping frame." )
204208 return False # no need to continue compute
205-
209+
206210 right , res = SlCameraStreamer .get_image_data (db .internal_state .annotator_right )
207211 if res == False :
208212 db .internal_state .invalid_images_count += 1
@@ -229,8 +233,8 @@ def compute(db) -> bool:
229233 # their IMUand still have access to the image functionality without issues in Isaac Sim
230234 lin_acc_x , lin_acc_y , lin_acc_z = 0 , 0 , 0
231235 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
234238 temp_orientation = imu_prim .get_world_pose ()[1 ]
235239 swp = copy .deepcopy (temp_orientation )
236240 orientation = [swp [0 ], - swp [1 ], - swp [3 ], - swp [2 ]]
@@ -244,12 +248,15 @@ def compute(db) -> bool:
244248 lin_acc_x = imu_reading .lin_acc_x
245249 lin_acc_y = imu_reading .lin_acc_y
246250 lin_acc_z = imu_reading .lin_acc_z
247-
251+
248252 # stream data
249253 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 ()
250257 res = db .internal_state .pyzed_streamer .stream (
251- left . tobytes () ,
252- right . tobytes () ,
258+ left_bytes ,
259+ right_bytes ,
253260 ts ,
254261 orientation [0 ],
255262 orientation [1 ],
@@ -266,7 +273,6 @@ def compute(db) -> bool:
266273 else :
267274 carb .log_verbose (f"Streamed at { ts } 2 rgb images and orientation: { orientation } " )
268275 db .internal_state .last_timestamp = current_time
269-
270276
271277 except Exception as error :
272278 # If anything causes your compute to fail report the error and return False
@@ -278,25 +284,28 @@ def compute(db) -> bool:
278284
279285 @staticmethod
280286 def release (node ):
281- carb .log_verbose ("Releasing resources" )
287+ carb .log_verbose ("Releasing resources" )
282288 try :
283289 state = SlCameraStreamerDatabase .per_node_internal_state (node )
284290 if state is not None :
285291 # disabling this could fix the render product issue (return empty arrays) when the scene reloads
286292 # but could also create issues when attaching cameras to render products
287293 if state .annotator_left :
288- state .annotator_left .detach ([ state . render_product_left ] )
294+ state .annotator_left .detach ()
289295 if state .render_product_left is not None :
296+ state .render_product_left .hydra_texture .set_updates_enabled (False )
290297 state .render_product_left .destroy ()
291298 if state .annotator_right :
292- state .annotator_right .detach ([ state . render_product_right ] )
299+ state .annotator_right .detach ()
293300 if state .render_product_right is not None :
301+ state .render_product_right .hydra_texture .set_updates_enabled (False )
294302 state .render_product_right .destroy ()
295-
303+
296304 if state .pyzed_streamer :
297305 state .pyzed_streamer .close ()
298306 # remove the streamer object when no longer needed
299307 del state .pyzed_streamer
308+
300309 _sensor .release_imu_sensor_interface (state .imu_sensor_interface )
301310 state .initialized = False
302311
0 commit comments