@@ -28,7 +28,9 @@ def create_turtlebot3_burger_with_omnigraph():
28
28
# Create turtlebot3_burger
29
29
turtlebot3_burger_prim_path = "/World/turtlebot3_burger_urdf"
30
30
camera_prim_path = "/World/turtlebot3_burger_urdf/base_scan/camera"
31
- camera_frame_id = "camera" # same as camera prim name
31
+ camera_frame_id = "camera" # same as USD camera prim name
32
+ lidar_prim_path = "/World/turtlebot3_burger_urdf/base_scan/lidar"
33
+ lidar_frame_id = "lidar" # same as USD lidar prim name
32
34
cmd_vel_topic = "/cmd_vel"
33
35
joint_name_0 = "wheel_left_joint"
34
36
joint_name_1 = "wheel_right_joint"
@@ -174,6 +176,7 @@ def create_turtlebot3_burger_with_omnigraph():
174
176
("PublishTF.inputs:targetPrims" , [
175
177
turtlebot3_burger_prim_path ,
176
178
camera_prim_path ,
179
+ lidar_prim_path ,
177
180
]),
178
181
("PublishTF.inputs:topicName" , "tf" ),
179
182
]
@@ -257,6 +260,45 @@ def create_turtlebot3_burger_with_omnigraph():
257
260
],
258
261
},
259
262
)
263
+ # OmniGraph for Publishing (RTX) Lidar Laser Scan and Point Cloud
264
+ # Ref: https://docs.omniverse.nvidia.com/isaacsim/latest/ros2_tutorials/tutorial_ros2_rtx_lidar.html
265
+ og .Controller .edit (
266
+ {"graph_path" : "/Graph/ROS_LidarRTX" , "evaluator_name" : "execution" },
267
+ {
268
+ og .Controller .Keys .CREATE_NODES : [
269
+ ("Context" , "omni.isaac.ros2_bridge.ROS2Context" ),
270
+ ("OnPlaybackTick" , "omni.graph.action.OnPlaybackTick" ),
271
+ ("RunOnce" , "omni.isaac.core_nodes.OgnIsaacRunOneSimulationFrame" ),
272
+ ("RenderProduct" , "omni.isaac.core_nodes.IsaacCreateRenderProduct" ),
273
+ ("PublishLidarLaserScan" , "omni.isaac.ros2_bridge.ROS2RtxLidarHelper" ),
274
+ ("PublishLidarPointCloud" , "omni.isaac.ros2_bridge.ROS2RtxLidarHelper" ),
275
+ ],
276
+ og .Controller .Keys .CONNECT : [
277
+ ("OnPlaybackTick.outputs:tick" , "RunOnce.inputs:execIn" ),
278
+ ("RunOnce.outputs:step" , "RenderProduct.inputs:execIn" ),
279
+ # PublishLidarLaserScan
280
+ ("RenderProduct.outputs:execOut" , "PublishLidarLaserScan.inputs:execIn" ),
281
+ ("RenderProduct.outputs:renderProductPath" , "PublishLidarLaserScan.inputs:renderProductPath" ),
282
+ ("Context.outputs:context" , "PublishLidarLaserScan.inputs:context" ),
283
+ # PublishLidarPointCloud
284
+ ("RenderProduct.outputs:execOut" , "PublishLidarPointCloud.inputs:execIn" ),
285
+ ("RenderProduct.outputs:renderProductPath" , "PublishLidarPointCloud.inputs:renderProductPath" ),
286
+ ("Context.outputs:context" , "PublishLidarPointCloud.inputs:context" ),
287
+ ],
288
+ og .Controller .Keys .SET_VALUES : [
289
+ ("RenderProduct.inputs:cameraPrim" , lidar_prim_path ),
290
+ # PublishLidarLaserScan
291
+ ("PublishLidarLaserScan.inputs:type" , "laser_scan" ),
292
+ ("PublishLidarLaserScan.inputs:topicName" , "laser_scan" ),
293
+ ("PublishLidarLaserScan.inputs:frameId" , lidar_frame_id ),
294
+ # PublishLidarPointCloud
295
+ ("PublishLidarPointCloud.inputs:type" , "point_cloud" ),
296
+ ("PublishLidarPointCloud.inputs:topicName" , "point_cloud" ),
297
+ ("PublishLidarPointCloud.inputs:frameId" , lidar_frame_id ),
298
+ ("PublishLidarPointCloud.inputs:fullScan" , True ),
299
+ ],
300
+ },
301
+ )
260
302
261
303
if __name__ == '__main__' :
262
304
# Ref: https://docs.omniverse.nvidia.com/dev-guide/latest/programmer_ref/extensions/enable-kit-extension.html
0 commit comments