Skip to content

autoware_lidar_frnet#

Purpose#

The autoware_lidar_frnet package is used for 3D semantic segmentation based on LiDAR data (x, y, z, intensity).

Inner-workings / Algorithms#

The implementation is based on the FRNet [1] project. It uses TensorRT library for data processing and network inference.

We trained the models using AWML [2].

Inputs / Outputs#

Input#

Name Type Description
~/input/pointcloud sensor_msgs::msg::PointCloud2 Input pointcloud.

Output#

Name Type Description
~/output/pointcloud/segmentation sensor_msgs::msg::PointCloud2 XYZ cloud with class ID field.
~/output/pointcloud/visualization sensor_msgs::msg::PointCloud2 XYZ cloud with RGB field.
~/output/pointcloud/filtered sensor_msgs::msg::PointCloud2 Input format cloud after removing specified point's class.
debug/cyclic_time_ms autoware_internal_debug_msgs::msg::Float64Stamped Cyclic time (ms).
debug/pipeline_latency_ms autoware_internal_debug_msgs::msg::Float64Stamped Pipeline latency time (ms).
debug/processing_time/preprocess_ms autoware_internal_debug_msgs::msg::Float64Stamped Preprocess (ms).
debug/processing_time/inference_ms autoware_internal_debug_msgs::msg::Float64Stamped Inference time (ms).
debug/processing_time/postprocess_ms autoware_internal_debug_msgs::msg::Float64Stamped Postprocess time (ms).
debug/processing_time/total_ms autoware_internal_debug_msgs::msg::Float64Stamped Total processing time (ms).
/diagnostics diagnostic_msgs::msg::DiagnosticArray Node diagnostics with respect to processing time constraints

Parameters#

FRNet node#

Name Type Description Default Range
onnx_path string A path to ONNX model file. $(var model_path)/frnet.onnx N/A
trt_precision string A precision of TensorRT engine. fp16 ['fp16', 'fp32']
fov_up_deg float LiDAR's upper elevation angle in degrees. 10.0 ≥-90.0
≤90.0
fov_down_deg float LiDAR's lower elevation angle in degrees. -30.0 ≥-90.0
≤90.0
frustum_width integer Width of the FRNet frustum in pixels. 480 ≥1
frustum_height integer Height of the FRNet frustum in pixels. 480 ≥1
interpolation_width integer Width of the FRNet LiDAR's points to 2D plane interpolation in pixels. 480 ≥1
interpolation_height integer Height of the FRNet LiDAR's points to 2D plane interpolation in pixels. 480 ≥1
score_threshold float A threshold value for the score model segmentation result. If the score is lower than this value, the point will obtain the 'unknown' class ID. 0.0 N/A
excluded_class_names array A list of class names to be excluded in filtered output cloud. ['driveable_surface'] N/A
palette array A sequence of RGB values for each class name. The length of the array must be 3 times the number of class names. [255, 120, 50, 255, 192, 203, 255, 255, 0, 0, 150, 245, 0, 255, 255, 255, 127, 0, 255, 0, 0, 255, 240, 150, 135, 60, 0, 160, 32, 240, 255, 0, 255, 139, 137, 137, 75, 0, 75, 150, 240, 80, 230, 230, 250, 0, 175, 0, 0, 0, 0] N/A

FRNet model#

Name Type Description Default Range
class_names array An array of class names which will be predicted. ['barrier', 'bicycle', 'bus', 'car', 'construction_vehicle', 'motorcycle', 'pedestrian', 'traffic_cone', 'trailer', 'truck', 'driveable_surface', 'other_flat', 'sidewalk', 'terrain', 'manmade', 'vegetation', 'unknown'] N/A
num_points array TensorRT optimization profile for number of points [min, opt, max]. [30000, 150000, 300000] N/A
num_unique_coors array TensorRT optimization profile for number of unique coordinates [min, opt, max]. [5000, 10000, 30000] N/A

FRNet diagnostics#

Name Type Description Default Range
max_allowed_processing_time_ms float A threshold value for the allowed processing time. If the processing time exceeds this value, it will be considered a warning state. [ms] 200 ≥0.0
max_acceptable_consecutive_delay_ms float A threshold value for the error state. If the duration since the last processing timestamp, which ended within max_allowed_processing_time_ms, exceeds this value, it will be considered an error state. [ms] 1000 ≥0.0
validation_callback_interval_ms float An interval value for a timer callback that checks whether the current state meets the max_acceptable_consecutive_delay_ms condition. [ms] 100 ≥1.0

The build_only option#

The autoware_lidar_frnet node has build_only option to build the TensorRT engine file from the ONNX file.

ros2 launch autoware_lidar_frnet lidar_frnet.launch.xml build_only:=true

Assumptions / Known limits#

This library operates on raw cloud data (bytes). It is assumed that the input pointcloud message has XYZIRC format:

[
  sensor_msgs.msg.PointField(name='x', offset=0, datatype=7, count=1),
  sensor_msgs.msg.PointField(name='y', offset=4, datatype=7, count=1),
  sensor_msgs.msg.PointField(name='z', offset=8, datatype=7, count=1),
  sensor_msgs.msg.PointField(name='intensity', offset=12, datatype=2, count=1),
  sensor_msgs.msg.PointField(name='ring', offset=13, datatype=2, count=1),
  sensor_msgs.msg.PointField(name='channel', offset=14, datatype=4, count=1)
]

This input may consist of other fields as well - shown format is required minimum. For debug purposes, you can validate your pointcloud topic using simple command:

ros2 topic echo <input_topic> --field fields

Trained Models#

The model was trained on the NuScenes dataset and is available in the Autoware artifacts.

[1] X. Xu, L. Kong, H. Shuai and Q. Liu, "FRNet: Frustum-Range Networks for Scalable LiDAR Segmentation" in IEEE Transactions on Image Processing, vol. 34, pp. 2173-2186, 2025, doi: 10.1109/TIP.2025.3550011.

[2] https://github.com/tier4/AWML.git

[3] https://xiangxu-0103.github.io/FRNet