Wrong Lidar semantic data got when the rotationRate is not zero

I built a simple semantic Lidar test scene, shown as:

The “Read Semantic Lidar Data” is a custom OmniGraph Node written in imitation of “Isaac Read Lidar Point Cloud Node” for acquiring both point cloud data and semantic data.

A Torus and a GroundPlane are placed in the stage, and their semantic IDs are 4 and 3, respectively.

However, when the Lidar’s rotationRate is set to a non-zero number, such as 10 in the figure above, the semantic data obtained has a large number of zeros, aka, unlabeled semantics.

Test code:

semantics = state.lidar_interface.get_semantic_data(state.lidar_prim_path)
print(semantics)

Part of the output:

[[0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]]
[[0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]]

The output when the rotationRate is 0:

[[0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
  ...
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]
 [0 0 0 0 0 0 4 4 4 4 4 4 3 3 3 3]]

The code of my OmniGraph Node:
OgnReadSemanticLidarData.ogn (1.6 KB)
OgnReadSemanticLidarData.py (6.0 KB)

This is a quick reproduction code snippet written in imitation of 9. Using Sensors: LIDAR:

import omni                                                     # Provides the core omniverse apis
import asyncio                                                  # Used to run sample asynchronously to not block rendering thread
from omni.isaac.range_sensor import _range_sensor               # Imports the python bindings to interact with lidar sensor
from pxr import UsdGeom, Gf, UsdPhysics, Semantics              # pxr usd imports used to create cube
from pxr import PhysicsSchemaTools
import numpy as np

stage = omni.usd.get_context().get_stage()                      # Used to access Geometry
timeline = omni.timeline.get_timeline_interface()               # Used to interact with simulation
lidarInterface = _range_sensor.acquire_lidar_sensor_interface() # Used to interact with the LIDAR

omni.kit.commands.execute('AddPhysicsSceneCommand',stage = stage, path='/World/PhysicsScene')
PhysicsSchemaTools.addGroundPlane(stage, "/World/groundPlane", "Z", 100, Gf.Vec3f(0, 0, 0), Gf.Vec3f(1.0))

result, path = omni.kit.commands.execute("CreateMeshPrimCommand", prim_type="Torus")
prim = stage.GetPrimAtPath("/World/Torus")
collisionAPI = UsdPhysics.CollisionAPI.Apply(prim)
sem = Semantics.SemanticsAPI.Apply(prim, "Semantics")
sem.CreateSemanticTypeAttr()
sem.CreateSemanticDataAttr()
sem.GetSemanticTypeAttr().Set("class")
sem.GetSemanticDataAttr().Set("Torus")

prim = stage.GetPrimAtPath("/World/groundPlane/collisionPlane")
collisionAPI = UsdPhysics.CollisionAPI.Apply(prim)
sem = Semantics.SemanticsAPI.Apply(prim, "Semantics")
sem.CreateSemanticTypeAttr()
sem.CreateSemanticDataAttr()
sem.GetSemanticTypeAttr().Set("class")
sem.GetSemanticDataAttr().Set("Ground")


lidarPath = "/lidar"
# Create lidar prim
result, prim = omni.kit.commands.execute(
            "RangeSensorCreateLidar",
            path=lidarPath,
            parent="/World",
            min_range=0.4,
            max_range=100.0,
            draw_points=True,
            draw_lines=False,
            horizontal_fov=360.0,
            vertical_fov=30.0,
            horizontal_resolution=0.4,
            vertical_resolution=2,
            rotation_rate=10.0,
            high_lod=True,
            yaw_offset=0.0,
            enable_semantics=True
        )
UsdGeom.XformCommonAPI(prim).SetTranslate((0.0, 0.0, 1.0))

# Get point cloud and semantic id for lidar hit points
async def get_lidar_param():
    await asyncio.sleep(1.0)
    timeline.pause()
    pointcloud = lidarInterface.get_point_cloud_data("/World"+lidarPath)
    semantics = lidarInterface.get_semantic_data("/World"+lidarPath)

    # print("Point Cloud", pointcloud)
    np.set_printoptions(threshold=np.inf)
    print("Semantic ID", semantics)
    
timeline.play()                                                 # Start the Simulation
asyncio.ensure_future(get_lidar_param())                        # Only ask for data after sweep is complete

When the rotation_rate is set to 10, the output semantics data contains a large number of zeros, while the output is correct when the rotation_rate is set to 0.

Thanks for the repro @brucexskk , will take a look and file a bug to fix this for the next release if there is an issue