Skip to content

dual_return_outlier_filter#

Purpose#

The purpose is to remove point cloud noise such as fog and rain and publish visibility as a diagnostic topic.

Inner-workings / Algorithms#

This node can remove rain and fog by considering the light reflected from the object in two stages according to the attenuation factor. The dual_return_outlier_filter is named because it removes noise using data that contains two types of return values separated by attenuation factor, as shown in the figure below.

outlier_filter-return_type

Therefore, in order to use this node, the sensor driver must publish custom data including return_type. please refer to PointXYZIRCAEDT data structure.

Another feature of this node is that it publishes visibility as a diagnostic topic. With this function, for example, in heavy rain, the sensing module can notify that the processing performance has reached its limit, which can lead to ensuring the safety of the vehicle.

In some complicated road scenes where normal objects also reflect the light in two stages, for instance plants, leaves, some plastic net etc, the visibility faces some drop in fine weather condition. To deal with that, optional settings of a region of interest (ROI) are added.

  1. Fixed_xyz_ROI mode: Visibility estimation based on the weak points in a fixed cuboid surrounding region of ego-vehicle, defined by x, y, z in base_link perspective.
  2. Fixed_azimuth_ROI mode: Visibility estimation based on the weak points in a fixed surrounding region of ego-vehicle, defined by azimuth and distance of LiDAR perspective.

When select 2 fixed ROI modes, due to the range of weak points is shrink, the sensitivity of visibility is decrease so that a trade of between weak_first_local_noise_threshold and visibility_threshold is needed.

outlier_filter-dual_return_overall

The figure below describe how the node works. outlier_filter-dual_return_detail

The below picture shows the ROI options.

outlier_filter-dual_return_ROI_setting_options

Inputs / Outputs#

This implementation inherits autoware::pointcloud_preprocessor::Filter class, please refer README.

Output#

Name Type Description
/dual_return_outlier_filter/frequency_image sensor_msgs::msg::Image The histogram image that represent visibility
/dual_return_outlier_filter/visibility autoware_internal_debug_msgs::msg::Float32Stamped A representation of visibility with a value from 0 to 1
/dual_return_outlier_filter/pointcloud_noise sensor_msgs::msg::Pointcloud2 The pointcloud removed as noise

Parameters#

Node Parameters#

This implementation inherits autoware::pointcloud_preprocessor::Filter class, please refer README.

Core Parameters#

Name Type Description Default Range
x_max float Maximum of x in meters for Fixed_xyz_ROI mode 18.0 N/A
x_min float Minimum of x in meters for Fixed_xyz_ROI mode -12.0 N/A
y_max float Maximum of y in meters for Fixed_xyz_ROI mode 2.0 N/A
y_min float Minimum of y in meters for Fixed_xyz_ROI mode -2.0 N/A
z_max float Maximum of z in meters for Fixed_xyz_ROI mode 10.0 N/A
z_min float Minimum of z in meters for Fixed_xyz_ROI mode 0.0 N/A
min_azimuth_deg float The left limit of azimuth in degrees for Fixed_azimuth_ROI mode 135.0 ≥0
≤360
max_azimuth_deg float The right limit of azimuth in degrees for Fixed_azimuth_ROI mode 225.0 ≥0
≤360
max_distance float The limit distance in meters for Fixed_azimuth_ROI mode 12.0 ≥0.0
vertical_bins integer The number of vertical bins for the visibility histogram 128 ≥1
max_azimuth_diff float The azimuth difference threshold in degrees for ring_outlier_filter 50.0 ≥0.0
weak_first_distance_ratio float The maximum allowed ratio between consecutive weak point distances 1.004 ≥0.0
general_distance_ratio float The maximum allowed ratio between consecutive normal point distances 1.03 ≥0.0
weak_first_local_noise_threshold integer If the number of outliers among weak points is less than the weak_first_local_noise_threshold in the (max_azimuth - min_azimuth) / horizontal_bins interval, all points within the interval will not be filtered out. 2 ≥0
roi_mode string roi mode Fixed_xyz_ROI ['Fixed_xyz_ROI', 'No_ROI', 'Fixed_azimuth_ROI']
visibility_error_threshold float When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes ERR 0.5 ≥0.0
≤1.0
visibility_warn_threshold float When the proportion of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN 0.7 ≥0.0
≤1.0

Assumptions / Known limits#

Not recommended for use as it is under development. Input data must be PointXYZIRCAEDT type data including return_type.

(Optional) Error detection and handling#

(Optional) Performance characterization#

(Optional) Future extensions / Unimplemented parts#