RTX Lidar: How to process Intensity ; Please provide a tutorial / example... #147
Replies: 2 comments 1 reply
-
Thank you for raising this important issue and for the detailed problem description. We will check with our team on how to address this and get back to you with an update as soon as possible. |
Beta Was this translation helpful? Give feedback.
-
@benjaminde I don't think it is possible to publish directly the intensities values to ROS2 with the current version of the simulator. If i understand correctly, Isaac Sim is using annotators to enrich the point cloud created by the Lidars. As of today, only three annotators are available for RTXLidar but only one supports outputting the intensities: Now we take a look at the registration of the annotators happening in this file To create the RTX Lidar, I used the python API. This So you can derive this LidarRtx class and override the def attach_annotator(
self,
annotator_name: Literal[
"IsaacComputeRTXLidarFlatScan",
"IsaacExtractRTXSensorPointCloudNoAccumulator",
"IsaacCreateRTXLidarScanBuffer",
],
) -> None:
"""Attach an annotator to the Lidar sensor.
Args:
param annotator_name (Literal): Name of the annotator to attach. Must be one of:
- "IsaacComputeRTXLidarFlatScan"
- "IsaacExtractRTXSensorPointCloudNoAccumulator"
- "IsaacCreateRTXLidarScanBuffer"
"""
if annotator_name in self._annotators:
carb.log_warn(
f"Annotator {annotator_name} already attached to {self._render_product_path}"
)
return
#annotator = rep.AnnotatorRegistry.get_annotator(annotator_name)
annotator = rep.AnnotatorRegistry.get_annotator(
annotator_name,
init_params={
# "outputAzimuth": True,
# "outputElevation": True
"outputIntensity": True,
},
)
annotator.attach([self._render_product_path])
self._annotators[annotator_name] = annotator
return and to retrieve you xyz + intensity data, just to a Last, to publish the data to ROS2, it would have to be done by hand (and NOT via the builtin PointCloud publisher as it does not accept intensity). I can confirm i was able to successfully publish and retrieve intensity values via ROS2: ![]() But the points are not correctly sorted along azimuth and elevation. |
Beta Was this translation helpful? Give feedback.
Uh oh!
There was an error while loading. Please reload this page.
-
Problem
Problem statement: How do we create an RTX lidar that can publish intensity data via ROS2.
What I want
Currently there is no clear documentation / tutorial / example on how to create an RTX lidar that can publish intensity data.
What is the recommended way of doing this?
We want to know how we can do this in 2 ways:
simulation.py
script that creates a headless simulation.Tutorial / example
The example can be very simple:
rviz2
+ show the intensity data.What I found on the documentation:
IsaacExtractRTXSensorPointCloud
but how do you use this?Tip
Reference to Nvidia Forum post:
I asked for this 9 jan 2025 for isaac sim 4.2.0 but still no results. This is something that is requested a LOT by the community.
See the Nvidia forum post RTX Lidar PointCloud 3D: How to set a custom intensity on objects? Changing the material properties have no effect
for more information.
Another post since Juli 01 2024 about the same topic here
Also in the Discord, nobody seems to be able to give me an example. (see here)
Beta Was this translation helpful? Give feedback.
All reactions