Skip to content

Ray Ground Filter#

Purpose#

The purpose of this node is that remove the ground points from the input pointcloud.

Inner-workings / Algorithms#

The points is separated radially (Ray), and the ground is classified for each Ray sequentially from the point close to ego-vehicle based on the geometric information such as the distance and angle between the points.

ray-xy

Inputs / Outputs#

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

Parameters#

Node Parameters#

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

Core Parameters#

ray-xz

Name Type Description Default Range
min_x float The parameter to set vehicle footprint manually -0.01 N/A
max_x float The parameter to set vehicle footprint manually 0.01 N/A
min_y float The parameter to set vehicle footprint manually -0.01 N/A
max_y float The parameter to set vehicle footprint manually 0.01 N/A
use_vehicle_footprint boolean use_vehicle_footprint false N/A
general_max_slope float The triangle created by general_max_slope is called the global cone. If the point is outside the global cone, it is judged to be a point that is not on the ground 8.0 N/A
local_max_slope float The triangle created by local_max_slope is called the local cone. This parameter is used for classifying points based on their continuity 6.0 N/A
initial_max_slope float Generally, the point where the object first hits is far from ego-vehicle because of sensor blind spot, so resolution is different from that point and thereafter, so this parameter exists to set a separate local_max_slope 3.0 N/A
radial_divider_angle float The angle of ray 1.0 N/A
min_height_threshold float This parameter is used instead of height_threshold because it's difficult to determine continuity in the local cone when the points are too close to each other 0.15 N/A
concentric_divider_distance float Only check points which radius is larger than concentric_divider_distance 0.0 N/A
reclass_distance_threshold float To check if point is to far from previous one, if so classify again 0.1 N/A
publish_processing_time_detail boolean publish_processing_time_detail false N/A

Assumptions / Known limits#

The input_frame is set as parameter but it must be fixed as base_link for the current algorithm.

(Optional) Error detection and handling#

(Optional) Performance characterization#

(Optional) Future extensions / Unimplemented parts#