Isaac Sim Version
5.0.0
Operating System
Ubuntu 22.04
GPU Information
- Model: “NVIDIA GeForce RTX 3050 Ti Laptop GPU” (4 GiB, sm_86, mempool enabled)
- Driver Version: 575.64.03
Topic Description
Detailed Description
I am trying to obtain semantic point clouds from an RtxLidar. To do this, I have opted to use the “IsaacCreateRTXLidarScanBuffer” annotator and put it inside a custom writer.
When creating the sensor, I set “omni:sensor:Core:auxOutputType” to EXTRA, with the aim of being able to receive both the object_id and the material_id.
However, using the simple_room asset as a playground, the object ID it reports is always 0, while the material ID is 31.
Could you tell me what I am doing wrong so that I can obtain a point cloud where each point has the ID associated with the object?
I am attaching the code I am using to obtain this result:
#!/usr/bin python3
import os
import sys
import numpy as np
import concurrent.futures
from plyfile import PlyData, PlyElement
from isaacsim import SimulationApp
simulation_app = SimulationApp({"headless": False})
import carb
import omni
from isaacsim.core.utils import stage
from isaacsim.storage.native import get_assets_root_path
import omni.replicator.core as rep
from pxr import Gf
def save_ply(points, intensities, obj_ids, filename):
if len(points) == 0:
return
vertices = np.array(
list(zip(points[:, 0], points[:, 1], points[:, 2], intensities, obj_ids)),
dtype=[("x", "f4"), ("y", "f4"), ("z", "f4"),
("intensity", "f4"), ("object_id", "i4")]
)
ply_element = PlyElement.describe(vertices, "vertex")
PlyData([ply_element], text=False).write(filename)
print(f"[Writer] Saved {filename} with {len(points)} points.")
# -----------------------------
# Custom LiDAR Writer
# -----------------------------
class LidarWriter(rep.Writer):
def __init__(self, output_dir="dataset_lidar"):
super().__init__()
self._frame_id = 0
self.file_path = os.path.join(output_dir, "Samples_5.0")
os.makedirs(self.file_path, exist_ok=True)
self.executor = concurrent.futures.ThreadPoolExecutor(max_workers=8)
# Create annotators
buffer_annotator = rep.AnnotatorRegistry.get_annotator("IsaacCreateRTXLidarScanBuffer")
buffer_annotator.initialize(
outputTimestamp=True, outputIntensity=True, outputObjectId=True, outputMaterialId=True,
)
self.annotators.append(buffer_annotator)
# no_accumulator = rep.AnnotatorRegistry.get_annotator("IsaacExtractRTXSensorPointCloudNoAccumulator")
# no_accumulator.initialize(outputObjectId=True)
# self.annotators.append(no_accumulator)
def close(self):
print("[Writer] Waiting until executor finish...")
self.executor.shutdown(wait=True)
print("[Writer] Executor finished")
def write(self, data):
# https://docs.isaacsim.omniverse.nvidia.com/5.0.0/sensors/isaacsim_sensors_rtx_annotators.html#isaaccreatertxlidarscanbuffer
if "IsaacCreateRTXLidarScanBuffer" in data:
lidar_data = data["IsaacCreateRTXLidarScanBuffer"]
points = lidar_data["data"]
intensities = lidar_data["intensity"]
timestamps = lidar_data["timestamp"]
obj_ids = lidar_data["objectId"]
mat_ids = lidar_data["materialId"]
if (len(points) > 0):
print(f"--- len points: {len(points)}")
print(f"--- intensities: {intensities}")
print(f"--- timestamps: {timestamps}")
print(f"--- obj ids: {obj_ids}")
print(f"--- mat ids: {mat_ids}")
filename = os.path.join(self.file_path, f"frame_{self._frame_id:06d}.ply")
self.executor.submit(save_ply, points, intensities, obj_ids, filename)
self._frame_id += 1
elif "IsaacExtractRTXSensorPointCloudNoAccumulator" in data:
# no_acumm_data = data["IsaacExtractRTXSensorPointCloudNoAccumulator"]
print("-------- IsaacExtractRTXSensorPointCloudNoAccumulator")
else:
print("Unkonwn accumulator type")
def shutdown(self):
self.executor.shutdown(wait=True)
def main():
rep.WriterRegistry.register(LidarWriter, "LidarWriter")
# -----------------------------
# Create scene
# -----------------------------
assets_root_path = get_assets_root_path()
if assets_root_path is None:
carb.log_error("Could not find Isaac Sim assets folder")
simulation_app.close()
sys.exit()
print("Loading environment...")
stage.add_reference_to_stage(
usd_path=assets_root_path + "/Isaac/Environments/Simple_Room/simple_room.usd",
# usd_path=assets_root_path + "/Isaac/Environments/Simple_Warehouse/warehouse.usd",
prim_path="/World/room"
)
simulation_app.update()
_, lidar_sensor = omni.kit.commands.execute(
"IsaacSensorCreateRtxLidar",
path="/sensor_lidar",
parent="World",
config="OS1",
variant="OS1_REV7_128ch10hz1024res",
translation=(0.0, 0, 1.0),
orientation=Gf.Quatd(1, 0, 0, 0)
)
prim = lidar_sensor.GetPrim()
if prim:
aux_attr = prim.GetAttribute("omni:sensor:Core:auxOutputType")
if aux_attr:
aux_attr.Set("EXTRA")
render_product = rep.create.render_product(lidar_sensor.GetPath(), resolution=(1, 1))
print("Environment propperly created")
dataset_writer = rep.WriterRegistry.get("LidarWriter")
out_dir = "isaac_lidar_dataset"
dataset_writer.initialize(output_dir = out_dir)
dataset_writer.attach([render_product])
timeline = omni.timeline.get_timeline_interface()
timeline.play()
while simulation_app.is_running():
simulation_app.update()
timeline.stop()
dataset_writer.close()
# dataset_writer.shutdown()
# writer.shutdown()
simulation_app.close()
if __name__=="__main__":
main()
GitHub gist: Custom writer to obtain semantic point clouds in Isaac Sim 5.0 · GitHub
Steps to Reproduce
- Install the pip plyfile library within the Python environment of Isaac Sim 5.0:
./isaac-sim-standalone-5.0.0-linux-x86_64/python.sh -m pip install plyfile
- Run the script provided with Isaac Sim’s Python interpreter.:
./isaac-sim-standalone-5.0.0-linux-x86_64/python.sh semantic_cloud_writer_50.py
Information/Error Messages
The console output for the first 4 point clouds is as follows:
— len points: 130879
— intensities: [0.19400656 0.22205523 0.20438667 … 0.220394 0.2316678 0.21543679]
— timestamps: [ 4909147619709 11454677780337 18000207940965 …
70865220938743953 70871766468904581 70878311999065209]
— obj ids: [0 0 0 … 0 0 0]
— mat ids: [31 31 31 … 31 31 31]
[Writer] Saved isaac_lidar_dataset/Samples_5.0/frame_000000.ply with 130879 points.
— len points: 130986
— intensities: [0.12332786 0.18055935 0.19800168 … 0.2124309 0.18653885 0.2195635 ]
— timestamps: [70888645690381791 70895191220542419 70901736750703047 …
70029630756145306 70036176286305934 70042721816466562]
— obj ids: [0 0 0 … 0 0 0]
— mat ids: [31 31 31 … 31 31 31]
[Writer] Saved isaac_lidar_dataset/Samples_5.0/frame_000001.ply with 130986 points.
— len points: 130978
— intensities: [0.21962778 0.21152599 0.22697149 … 0.17913553 0.22516626 0.1949715 ]
— timestamps: [70049782742702830 70056328272863458 70062873803024086 …
69190772103433642 69197317633594270 69203863163754898]
— obj ids: [0 0 0 … 0 0 0]
— mat ids: [31 31 31 … 31 31 31]
[Writer] Saved isaac_lidar_dataset/Samples_5.0/frame_000002.ply with 130978 points.
— len points: 130978
— intensities: [0.14541683 0.21475679 0.19176859 … 0.15119787 0.1980043 0.21636812]
— timestamps: [69210924089991166 69217469620151794 69224015150312422 …
68351909155754681 68358454685915309 68365000216075937]
— obj ids: [0 0 0 … 0 0 0]
— mat ids: [31 31 31 … 31 31 31]
[Writer] Saved isaac_lidar_dataset/Samples_5.0/frame_000003.ply with 130978 points.
— len points: 130991
— intensities: [0.2087737 0.21968542 0.23283759 … 0.15557158 0.17079622 0.22607362]
— timestamps: [68372061142312205 68378606672472833 68385152202633461 …
67509777737962703 67516323268123331 67522868798283959]
— obj ids: [0 0 0 … 0 0 0]
— mat ids: [31 31 31 … 31 31 31]
[Writer] Saved isaac_lidar_dataset/Samples_5.0/frame_000004.ply with 130991 points.
Screenshots or Videos
Attached is the output of point cloud 4 (in CloudCompare), using the intensity value as the color:
Attached is the output of point cloud 4, using the object_id value as the color:
Additional Information
What I’ve Tried
(Describe any troubleshooting steps you’ve already taken)
I created this same code in Isaac Sim 4.5 using “RtxSensorCpuIsaacCreateRTXLidarScanBuffer.” However, the problem is that in this case, the clouds are not complete, and the object_ids are not assigned correctly.