Seg fault when activating ros2 bridge in python

Isaac Sim Version

4.5.0

Operating System

Ubuntu 22.04

GPU Information

  • Model: 4080 Laptop
  • Driver Version: 560.35.03
  • CUDA Version: 12.6

Topic Description

Detailed Description

I am attempting to run a python script that will automatically load a scene with the ros2 bridge enabled. I can manually launch Isaac Sim with the ros2 bridge and load the scene, and it works fine. I referenced the example scripts in /isaacsim/standalone_examples/api/isaacsim.ros2.bridge and /isaacsim/standalone_examples/api/isaacsim.simulation_app to create my python script, it seems correct to me but always results in a seg fault. The script loads Isaac Sim and the scene fine when I remove the 2 lines enabling the ros2 bridge, just without any connection to ros2.

Code

from isaacsim import SimulationApp

# This sample loads a usd stage and starts simulation
CONFIG = {
    "width": 1280,
    "height": 720,
    "sync_loads": True,
    "headless": False,
    "renderer": "RaytracedLighting",
}

usd_path = "omniverse://localhost/Projects/zero-to-slam/scene.usd"

# Start the omniverse application
simulation = SimulationApp(launch_config=CONFIG)

import carb
import omni

from isaacsim.core.utils.extensions import enable_extension
enable_extension("isaacsim.ros2.bridge")

omni.usd.get_context().open_stage(usd_path)

# Wait two frames so that stage starts loading
simulation.update()
simulation.update()

print("Loading stage...")
from isaacsim.core.utils.stage import is_stage_loading

while is_stage_loading():
    simulation.update()
print("Loading Complete")
omni.timeline.get_timeline_interface().play()

while simulation.is_running():
    # Run in realtime mode, we don't specify the step size
    simulation.update()

omni.timeline.get_timeline_interface().stop()
simulation.close()

Error Messages

[4.759s] Simulation App Starting
2025-02-24 14:41:04 [5,096ms] [Warning] [rtx.scenedb.plugin] SceneDbContext : TLAS limit buffer size 7374781440
2025-02-24 14:41:04 [5,096ms] [Warning] [rtx.scenedb.plugin] SceneDbContext : TLAS limit : valid false, within: false
2025-02-24 14:41:04 [5,096ms] [Warning] [rtx.scenedb.plugin] SceneDbContext : TLAS limit : decrement: 167690, decrement size: 7301033856
2025-02-24 14:41:04 [5,096ms] [Warning] [rtx.scenedb.plugin] SceneDbContext : New limit 9748724 (slope: 439, intercept: 13179904)
2025-02-24 14:41:04 [5,096ms] [Warning] [rtx.scenedb.plugin] SceneDbContext : TLAS limit buffer size 4287352704
2025-02-24 14:41:04 [5,096ms] [Warning] [rtx.scenedb.plugin] SceneDbContext : TLAS limit : valid true, within: true
[5.123s] app ready
2025-02-24 14:41:04 [5,207ms] [Warning] [omni.usd-abi.plugin] No setting was found for '/rtx-defaults-transient/meshlights/forceDisable'
2025-02-24 14:41:04 [5,310ms] [Warning] [omni.usd-abi.plugin] No setting was found for '/rtx-defaults/post/dlss/execMode'
[8.484s] Simulation App Startup Complete
[8.498s] [ext: isaacsim.ros2.bridge-4.1.15] startup
[8.526s] Attempting to load system rclpy
[8.556s] rclpy loaded
2025-02-24 14:41:10 [10,892ms] [Warning] [omni.timeline.plugin] Deprecated: direct use of ITimeline callbacks is deprecated. Use ITimeline::getTimeline (Python: omni.timeline.get_timeline_interface) instead.
Fatal Python error: Segmentation fault

Thread 0x00007b2c18a00640 (most recent call first):
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/concurrent/futures/thread.py", line 81 in _worker
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 953 in run
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 1016 in _bootstrap_inner
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 973 in _bootstrap

Thread 0x00007b2e17e00640 (most recent call first):
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/concurrent/futures/thread.py", line 81 in _worker
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 953 in run
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 1016 in _bootstrap_inner
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 973 in _bootstrap

Thread 0x00007b2e1da00640 (most recent call first):
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/concurrent/futures/thread.py", line 81 in _worker
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 953 in run
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 1016 in _bootstrap_inner
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 973 in _bootstrap

Thread 0x00007b2e1f000640 (most recent call first):
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/concurrent/futures/thread.py", line 81 in _worker
  File "/home/kyler/isaacsim/kit/python/lib/python3.10/threading.py", line 953 in run
  File "/home/kyler/isaacsim/python.sh: line 41: 39596 Segmentation fault      (core dumped) $python_exe "$@" $args
There was an error running python

Not sure if it will help your particular case, but something similar happened in 4.2.0.

Stepping the simulation a couple of times right after enabling the ros2 bridge and before doing anything else made it go away for me.

I haven’t encountered this issue. However, please review the solution provided in Python segfault with action graph in scene.

This worked lol. Thank you, it might’ve taken a while to figure that out

Corrected code:

# Copyright (c) 2020-2024, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
#

from isaacsim import SimulationApp

# This sample loads a usd stage and starts simulation
CONFIG = {
    "width": 1280,
    "height": 720,
    "sync_loads": True,
    "headless": False,
    "renderer": "RaytracedLighting",
}

usd_path = "omniverse://localhost/Projects/zero-to-slam/scene.usd"

# Start the omniverse application
simulation = SimulationApp(launch_config=CONFIG)

import carb
import omni

from isaacsim.core.utils.extensions import enable_extension
enable_extension("isaacsim.ros2.bridge")

# Wait two frames so that stage starts loading
simulation.update()
simulation.update()

omni.usd.get_context().open_stage(usd_path)

# Wait two frames so that stage starts loading
simulation.update()
simulation.update()

print("Loading stage...")
from isaacsim.core.utils.stage import is_stage_loading

while is_stage_loading():
    simulation.update()
print("Loading Complete")
omni.timeline.get_timeline_interface().play()

while simulation.is_running():
    # Run in realtime mode, we don't specify the step size
    simulation.update()

omni.timeline.get_timeline_interface().stop()
simulation.close()

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.