Accessing data from multiple RTX Lidars

Hello everyone,

I have a problem when trying to access the data from multiple RTX Lidars. I use this code, to create a Lidar

_, sensor1 = omni.kit.commands.execute(
    "IsaacSensorCreateRtxLidar",
    path="/World/path/to/sensor1",
    parent=None,
    config=lidar_config,
    translation=(0, 0, 0),
    orientation=Gf.Quatd(0.0, 1.0, 0.0, 0.0),  # (QW, QX, QY, QZ)
)
_, render_product_path_sensor1 = create_hydra_texture([1, 1], sensor1.GetPath().pathString)

_, sensor2 = omni.kit.commands.execute(
    "IsaacSensorCreateRtxLidar",
    path="/World/path/to/sensor2",
    parent=None,
    config=lidar_config,
    translation=(0, 0, 0),
    orientation=Gf.Quatd(0.0, 1.0, 0.0, 0.0),  # (QW, QX, QY, QZ)
)
_, render_product_path_sensor2 = create_hydra_texture([1, 1], sensor2.GetPath().pathString)

the i create annotators like this:

annotator_sensor1 = rep.AnnotatorRegistry.get_annotator(
    "RtxSensorCpuIsaacCreateRTXLidarScanBuffer"
)
annotator_sensor1.initialize(keepOnlyPositiveDistance=True)
annotator_sensor1.initialize(transformPoints=False)
annotator_sensor1.initialize(outputAzimuth=True)
annotator_sensor1.initialize(outputTimestamp=True)
annotator_sensor1.attach([render_product_path_sensor1])

annotator_sensor2 = rep.AnnotatorRegistry.get_annotator(
    "RtxSensorCpuIsaacCreateRTXLidarScanBuffer"
)
annotator_sensor2.initialize(keepOnlyPositiveDistance=True)
annotator_sensor2.initialize(transformPoints=False)
annotator_sensor2.initialize(outputAzimuth=True)
annotator_sensor2.initialize(outputTimestamp=True)
annotator_sensor2.attach([render_product_path_sensor2])

Now when I try to access data like this, it doesn`t work. When performing all of this with only one Lidar, it works fine.

 while simulation_app.is_running():
        simulation_app.update()
        data_sensor1 = annotator_sensor1.get_data()
        distances = data_sensor2.get("distance")
        scan_size = distances.size
        print(f"[1]: distances_size = {scan_size}")

        data_sensor2 = annotator_sensor2.get_data()
        distances = data_sensor2.get("distance")
        scan_size = distances.size
        print(f"[2]: distances_size = {scan_size}")

In the action graph the whole pipeline is generated twice, but i figured out, that the SD On New Frame and Frame Gate Nodes are only generated once.

Maybe someone can help, to access the RTX Lidar data from multiple sensors.

You have to keep a reference to the hydra texture of both rtx sensors.

This is the way I did it:

        texture_2d_lidar, render_product_path_2d_lidar = utils.render_product.create_hydra_texture(
            [1, 1], lidar_2d.GetPath().pathString
        )
        texture_3d_lidar, render_product_path_3d_lidar = utils.render_product.create_hydra_texture(
            [1, 1], lidar_3d.GetPath().pathString
        )

        hydra_textures = [texture_2d_lidar, texture_3d_lidar]

Additionally try to initialise every sensor only once and add all arguments into one function call.
Like this:

annotator_sensor1.initialize(keepOnlyPositiveDistance=True, transformPoints=False, outputAzimuth=True, outputTimestamp=True)

As far as I remember it will otherwise just override the previously set options.

2 Likes

@wueestry thanks!

I somehow assumed that the first value was a boolean, because of the documentation of a similar called function. And yes the annotator should be initialized the way you provided. On the last Isaac Sim version, I had to do it the other way, because of a bug or something.

Thanks for your reply!

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