Isaac Sim RTX LiDAR Sensor not working if created inside a function

Hello everyone,

I’ve recently followed the guide for creating an RTX LiDAR Sensor within Isaac sim. However i encountered a strange behaviour if i try to create the RTX LiDAR Sensor within a function. When i try to call a function in which i create the RTX LiDAR Sensor it will be created but it won’t shoot out any rays and thus creates an empty pointcloud. When created outside a function everything works perfectly fine.

Is used the following standalone python code to run a headless Isaac sim instance in an Isaac Sim docker container:

from omni.isaac.kit import SimulationApp

CONFIG = {
    "width": 1280,
    "height": 720,
    "window_width": 1920,
    "window_height": 1080,
    "headless": True,
    "renderer": "RayTracedLighting",
    "display_options": 3286,  # Set display options to show default grid
}

# Example for creating a RTX lidar sensor and publishing PCL data
simulation_app = SimulationApp(launch_config=CONFIG)
import omni
import omni.kit.viewport.utility
import omni.replicator.core as rep
from omni.isaac.core import World
from omni.isaac.core.utils.stage import create_new_stage
from omni.isaac.core.utils.extensions import enable_extension
from omni.isaac.core.utils.render_product import create_hydra_texture
from pxr import Gf

simulation_app.update()

# enable livestream
simulation_app.set_setting("/app/window/drawMouse", True)
simulation_app.set_setting("/app/livestream/proto", "ws")
simulation_app.set_setting("/app/livestream/websocket/framerate_limit", 120)
simulation_app.set_setting("/ngx/enabled", False)
enable_extension("omni.kit.livestream.native")

def load():
    world_settings = {"physics_dt": 1.0 / 60.0, "stage_units_in_meters": 1.0, "rendering_dt": 1.0 / 60.0}

    create_new_stage()
    world = World(**world_settings)
    world.scene.add_default_ground_plane()

def rtx():
    # Create the lidar sensor that generates data into "RtxSensorCpu"
    # Sensor needs to be rotated 90 degrees about X so that its Z up

    # Possible options are Example_Rotary and Example_Solid_State
    # drive sim applies 0.5,-0.5,-0.5,w(-0.5), we have to apply the reverse

    lidar_config = "Example_Rotary"
    _, sensor = omni.kit.commands.execute(
        "IsaacSensorCreateRtxLidar",
        path="/sensor",
        parent=None,
        config=lidar_config,
        translation=(0, 0, 1.0),
        orientation=Gf.Quatd(0.5, 0.5, -0.5, -0.5),  # Gf.Quatd is w,i,j,k
    )
    _, render_product_path = create_hydra_texture([1, 1], sensor.GetPath().pathString)

    # Create the debug draw pipeline in the post process graph
    writer = rep.writers.get("RtxLidar" + "DebugDrawPointCloud")
    writer.attach([render_product_path])
    print("rtx lidar 1 done")

load()
rtx()

lidar_config = "Example_Rotary"
_, sensor = omni.kit.commands.execute(
    "IsaacSensorCreateRtxLidar",
    path="/sensor2",
    parent=None,
    config=lidar_config,
    translation=(2.0, 0, 1.0),
    orientation=Gf.Quatd(0.5, 0.5, -0.5, -0.5),  # Gf.Quatd is w,i,j,k
)
_, render_product_path = create_hydra_texture([1, 1], sensor.GetPath().pathString)

# Create the debug draw pipeline in the post process graph
writer = rep.writers.get("RtxLidar" + "DebugDrawPointCloud")
writer.attach([render_product_path])
print("rtx lidar 2 done")

print("Is running...")
while simulation_app.is_running():
    simulation_app.update()

# cleanup and shutdown
simulation_app.close()

Here is what it looks like when running the standalone code:
Omniverse-Streaming-Client-2023-09-06-14-58-17

Im curious if there is an answer for this, since this seems very strange for me.
Many thanks in advance

2 Likes

I can reproduce this behavior on my machine

You should be able to make multiple rtx lidar. we have an automated test that makes up to 8 and it works fine. Maybe the problem is with the point cloud debug viewer? At the moment, only one debug view node at a time will work.

Publish multiple RTX LiDAR with ROS2 may give you more info.

I tried spawning only one RTX LiDAR sensor now, but inside a function. I used the same code as in my post above without creating the second RTX LiDAR sensor.
When i launched the standalone script and then pressed on play, the debug viewer didn’t show any points and printing out the point cloud from the Omni Graph Node gave an empty array. I then added another RTX LiDAR sensor with the scripting window and the debug viewer successfully showed the point cloud from the sensor.
Below is a gif that shows my whole process of doing so:
Omniverse-Streaming-Client-2023-09-15-16-34-37

Is it possible that maybe something goes wrong because the RTX LiDAR sensor is not created within an async function, like the function you posted in the forum post Publish multiple RTX LiDAR with ROS2?

Yup, I see that happening too. It appears to be the SdOnNewRenderProduct frame node is not outputting the render product, even though it is in the input… will have to look into this further.

I have a workaround. It looks like the hydra texture created by create_hydra_texture goes away when it goes out of scope of the rtx() function. If you return it, and keep it in a variable, then it works for me.

So at the end of your rtx() function, do:
return _
and instead of just calling, rtx(), you want to now save the result in a variable.
hydra_texture = rtx()

you can also use the rep.create.render_product function and the return from that can be attached to the writer instead of the render_product_path. In that case you don’t have to keep hold of anything yourself.

    hydra_texture = rep.create.render_product(sensor.GetPath(), [1, 1], name="Isaac")
    writer = rep.writers.get("" + "RtxLidar" + "DebugDrawPointCloud" + "Buffer")
    writer.attach([hydra_texture])

should fork in isaac 2023.1.0. I’m not sure if rep.create.render_product is available in 2022.2.1

Awesome! That worked for me too. My first try to solve this problem was to return the writer and render_product_path and that didn’t work, it didn’t came to my mind to return the hydra texture. Going further, i tried out, what would happen if i would call such a function inside a class and it turns out, saving the hydra texture as a class attribute also solves this problem.
Thanks again for the help :)

1 Like

Im currently working with Isaac Sim 2022.2.1, i looked over the API docs and couldn’t find a function called render_product under rep.create

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