Isaac Sim Version: 4.0.0
I am getting cuda error when trying to create cameras and correspoding action graph with multi-gpu setup.
Following steps( in isaac-sim container) are followed:
- Open Headless webrtc
$ export RMW_IMPLEMENTATION=rmw_fastrtps_cpp
$ export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/isaac-sim/exts/omni.isaac.ros2_bridge/humble/lib
$ /isaac-sim/isaac-sim.headless.webrtc.sh --allow-root - Open script editor and paste following script
import omni import time import omni.isaac.core.utils.extensions as extensions_utils # noqa: E402 import omni.graph.core as og from omni.isaac.sensor import Camera from omni.isaac.core_nodes.scripts.utils import set_target_prims def create_graph(cam_name: str, rgb: bool= False, depth: bool= False): graph_path = f"/World/realsense_{cam_name}" width = 240 height = 425 camera_prims = [] nodes = [] nodes_with_values = [] connection = [] if depth: camera_prims.append(f"/World/{cam_name}_depth") if rgb: camera_prims.append(f"/World/{cam_name}_rgb") for cam in camera_prims: camera = Camera( prim_path=cam, # frequency=20, resolution=(width, height), ) camera.initialize() nodes_common = [('OnPlaybackTick', 'omni.graph.action.OnPlaybackTick'), ('ROS2Context', 'omni.isaac.ros2_bridge.ROS2Context'), ('IsaacReadSimTime', 'omni.isaac.core_nodes.IsaacReadSimulationTime') ] nodes_depth = [ (f'render_{cam_name}_depth', 'omni.isaac.core_nodes.IsaacCreateRenderProduct'), (f'ros2_{cam_name}_depth', 'omni.isaac.ros2_bridge.ROS2CameraHelper'), (f'read_{cam_name}_info_depth', 'omni.isaac.core_nodes.IsaacReadCameraInfo'), (f'ros2_{cam_name}_info_depth', 'omni.isaac.ros2_bridge.ROS2PublishCameraInfo')] nodes_rgb = [ (f'render_{cam_name}_rgb', 'omni.isaac.core_nodes.IsaacCreateRenderProduct'), (f'ros2_{cam_name}_rgb', 'omni.isaac.ros2_bridge.ROS2CameraHelper'), (f'read_{cam_name}_info_rgb', 'omni.isaac.core_nodes.IsaacReadCameraInfo'), (f'ros2_{cam_name}_info_rgb', 'omni.isaac.ros2_bridge.ROS2PublishCameraInfo'), ] nodes_with_values_common = [('ROS2Context.inputs:useDomainIDEnvVar', True)] nodes_with_values_depth = [ (f'render_{cam_name}_depth.inputs:width', height), (f'render_{cam_name}_depth.inputs:height', width), (f'ros2_{cam_name}_depth.inputs:topicName', f'/{cam_name}_depth/depth/image_raw'), (f'ros2_{cam_name}_depth.inputs:frameId', f'{cam_name}_depth_link'), (f'ros2_{cam_name}_depth.inputs:type', 'depth'), (f'ros2_{cam_name}_info_depth.inputs:topicName', f'/{cam_name}_depth/depth/camera_info'), (f'ros2_{cam_name}_info_depth.inputs:frameId', f'{cam_name}_depth_link') ] nodes_with_values_rgb = [ (f'render_{cam_name}_rgb.inputs:width', height), (f'render_{cam_name}_rgb.inputs:height', width), (f'ros2_{cam_name}_rgb.inputs:topicName', f'/{cam_name}_rgb/image_raw'), (f'ros2_{cam_name}_rgb.inputs:frameId', f'{cam_name}_rgb_link'), (f'ros2_{cam_name}_rgb.inputs:type', 'rgb'), (f'ros2_{cam_name}_info_rgb.inputs:topicName', f'/{cam_name}_rgb/camera_info'), (f'ros2_{cam_name}_info_rgb.inputs:frameId', f'{cam_name}_rgb_link'), ] connection_with_rgb = [ ('OnPlaybackTick.outputs:tick', f'render_{cam_name}_rgb.inputs:execIn'), (f'render_{cam_name}_rgb.outputs:execOut', f'ros2_{cam_name}_rgb.inputs:execIn'), (f'render_{cam_name}_rgb.outputs:renderProductPath', f'ros2_{cam_name}_rgb.inputs:renderProductPath'), ('ROS2Context.outputs:context', f'ros2_{cam_name}_rgb.inputs:context'), (f'render_{cam_name}_rgb.outputs:renderProductPath', f'read_{cam_name}_info_rgb.inputs:renderProductPath'), ('IsaacReadSimTime.outputs:simulationTime', f'ros2_{cam_name}_info_rgb.inputs:timeStamp'), ('OnPlaybackTick.outputs:tick', f'ros2_{cam_name}_info_rgb.inputs:execIn'), ('ROS2Context.outputs:context', f'ros2_{cam_name}_info_rgb.inputs:context'), (f'read_{cam_name}_info_rgb.outputs:focalLength', f'ros2_{cam_name}_info_rgb.inputs:focalLength'), (f'read_{cam_name}_info_rgb.outputs:height', f'ros2_{cam_name}_info_rgb.inputs:height'), (f'read_{cam_name}_info_rgb.outputs:width', f'ros2_{cam_name}_info_rgb.inputs:width'), (f'read_{cam_name}_info_rgb.outputs:horizontalAperture', f'ros2_{cam_name}_info_rgb.inputs:horizontalAperture'), (f'read_{cam_name}_info_rgb.outputs:horizontalOffset', f'ros2_{cam_name}_info_rgb.inputs:horizontalOffset'), (f'read_{cam_name}_info_rgb.outputs:physicalDistortionCoefficients', f'ros2_{cam_name}_info_rgb.inputs:physicalDistortionCoefficients'), (f'read_{cam_name}_info_rgb.outputs:physicalDistortionModel', f'ros2_{cam_name}_info_rgb.inputs:physicalDistortionModel'), (f'read_{cam_name}_info_rgb.outputs:projectionType', f'ros2_{cam_name}_info_rgb.inputs:projectionType'), (f'read_{cam_name}_info_rgb.outputs:verticalAperture', f'ros2_{cam_name}_info_rgb.inputs:verticalAperture'), (f'read_{cam_name}_info_rgb.outputs:verticalOffset', f'ros2_{cam_name}_info_rgb.inputs:verticalOffset'), ] connection_with_depth = [ ('OnPlaybackTick.outputs:tick', f'render_{cam_name}_depth.inputs:execIn'), (f'render_{cam_name}_depth.outputs:execOut', f'ros2_{cam_name}_depth.inputs:execIn'), (f'render_{cam_name}_depth.outputs:renderProductPath', f'ros2_{cam_name}_depth.inputs:renderProductPath'), (f'ROS2Context.outputs:context', f'ros2_{cam_name}_depth.inputs:context'), (f'render_{cam_name}_depth.outputs:renderProductPath', f'read_{cam_name}_info_depth.inputs:renderProductPath'), ('IsaacReadSimTime.outputs:simulationTime', f'ros2_{cam_name}_info_depth.inputs:timeStamp'), ('OnPlaybackTick.outputs:tick', f'ros2_{cam_name}_info_depth.inputs:execIn'), ('ROS2Context.outputs:context', f'ros2_{cam_name}_info_depth.inputs:context'), (f'read_{cam_name}_info_depth.outputs:focalLength', f'ros2_{cam_name}_info_depth.inputs:focalLength'), (f'read_{cam_name}_info_depth.outputs:height', f'ros2_{cam_name}_info_depth.inputs:height'), (f'read_{cam_name}_info_depth.outputs:width', f'ros2_{cam_name}_info_depth.inputs:width'), (f'read_{cam_name}_info_depth.outputs:horizontalAperture', f'ros2_{cam_name}_info_depth.inputs:horizontalAperture'), (f'read_{cam_name}_info_depth.outputs:horizontalOffset', f'ros2_{cam_name}_info_depth.inputs:horizontalOffset'), (f'read_{cam_name}_info_depth.outputs:physicalDistortionCoefficients', f'ros2_{cam_name}_info_depth.inputs:physicalDistortionCoefficients'), (f'read_{cam_name}_info_depth.outputs:physicalDistortionModel', f'ros2_{cam_name}_info_depth.inputs:physicalDistortionModel'), (f'read_{cam_name}_info_depth.outputs:projectionType', f'ros2_{cam_name}_info_depth.inputs:projectionType'), (f'read_{cam_name}_info_depth.outputs:verticalAperture', f'ros2_{cam_name}_info_depth.inputs:verticalAperture'), (f'read_{cam_name}_info_depth.outputs:verticalOffset', f'ros2_{cam_name}_info_depth.inputs:verticalOffset') ] nodes = nodes_common nodes_with_values = nodes_with_values_common if rgb: nodes += nodes_rgb nodes_with_values += nodes_with_values_rgb connection += connection_with_rgb if depth: nodes += nodes_depth nodes_with_values += nodes_with_values_depth connection += connection_with_depth if len(connection) != 0: keys = og.Controller.Keys og.Controller.edit( {"graph_path": graph_path, "evaluator_name": "execution"}, { keys.CREATE_NODES: nodes, keys.SET_VALUES: nodes_with_values, keys.CONNECT: connection, }, ) for cam in camera_prims: set_target_prims( primPath=graph_path + "/" + f"render_{cam.split('/')[-1]}", inputName="inputs:cameraPrim", targetPrimPaths=[cam], ) if __name__ == "__main__": is_depth=True is_rgb=False number_of_cameras=2 for cam_num in range(number_of_cameras): create_graph(cam_name=f"cam{cam_num}", depth=is_depth, rgb=is_rgb)
- Start Timeline (Play)
- Start the Script (Ctrl-Enter)
Error:
(this happens when atleast 2 cameras are created)
2024-10-04 09:05:36 [265,128ms] [Error] [omni.syntheticdata.plugin] CUDA error 801: cudaErrorNotSupported - operation not supported)
2024-10-04 09:05:36 [265,128ms] [Error] [omni.syntheticdata.plugin] OgnSdUtils::copyTextureToBufferNoStride : cannot access input texture.
2024-10-04 09:05:36 [265,128ms] [Error] [omni.syntheticdata.plugin] CUDA error 801: cudaErrorNotSupported - operation not supported)
2024-10-04 09:05:36 [265,128ms] [Error] [omni.syntheticdata.plugin] CUDA ERROR at ../../../source/extensions/omni.syntheticdata/nodes/OgnSdCopyCuda.cu:197
and when I tried to open the generated graph in GUI, following error is seen on terminal:
[295,574ms] [Error] [carb.cudainterop.plugin] CUDA error 700: cudaErrorIllegalAddress - an illegal memory access was encountered)
2024-10-04 09:06:07 [295,574ms] [Error] [carb.cudainterop.plugin] Failed to allocate CUDA device memory (size: 408000).
2024-10-04 09:06:07 [295,574ms] [Error] [omni.syntheticdata.plugin] SdRenderVarToRawArray cannot allocate working cuda buffer of size (408000)
2024-10-04 09:06:07 [295,597ms] [Error] [carb.livestream-rtc.plugin] nvstPushStreamData error for eye 0, stream 0x7f7af808a9c0: 0x800b0000
2024-10-04 09:06:07 [295,602ms] [Error] [carb.cudainterop.plugin] CUDA error 700: cudaErrorIllegalAddress - an illegal memory access was encountered)
2024-10-04 09:06:07 [295,602ms] [Error] [carb.cudainterop.plugin] Failed to wait on external semaphore in CUDA.
2024-10-04 09:06:07 [295,602ms] [Error] [gpu.foundation.plugin] Wait for external semaphore failed in CUDA submission in command list "Render graph command list (Render queue 0, device 0, frame submission index 0)"
2024-10-04 09:06:07 [295,604ms] [Error] [carb.cudainterop.plugin] CUDA error 700: cudaErrorIllegalAddress - an illegal memory access was encountered)
2024-10-04 09:06:07 [295,604ms] [Error] [carb.cudainterop.plugin] Failed to wait on external semaphore in CUDA.
2024-10-04 09:06:07 [295,604ms] [Error] [gpu.foundation.plugin] Wait for external semaphore failed in CUDA submission in command list "Render graph command list (Render queue 0, device 1, frame submission index 2)"
2024-10-04 09:06:37 [325,604ms] [Error] [gpu.foundation.plugin] Submission barrier "CUDA event dependency in MGPU resource" timeout in command list "Render graph command list (Render queue 0, device 0, frame submission index 2)"!
2024-10-04 09:06:37 [325,604ms] [Error] [gpu.foundation.plugin] Wait count: 1, Received signals: 0:
2024-10-04 09:06:37 [325,604ms] [Error] [carb.cudainterop.plugin] CUDA error 700: cudaErrorIllegalAddress - an illegal memory access was encountered)
2024-10-04 09:06:37 [325,604ms] [Error] [carb.cudainterop.plugin] Failed to wait on CUDA event .
Note:
Same script works when isaac sim is launched by adding following flag:
--/renderer/multiGpu/enabled=False
Logs
multigpu disabled:
multigpu_enabled_kit_20241004_093327.log (1.2 MB)
multigpu enabled:
multigpu_enabled_kit_20241004_093327.log (1.2 MB)
So are there any settings that i need to ensure to run in multi gpu setup ?