autoware_ground_segmentation
Purpose
The autoware_ground_segmentation
is a node that remove the ground points from the input pointcloud.
Inner-workings / Algorithms
Detail description of each ground segmentation algorithm is in the following links.
Filter Name |
Description |
Detail |
ray_ground_filter |
A method of removing the ground based on the geometrical relationship between points lined up on radiation |
link |
scan_ground_filter |
Almost the same method as ray_ground_filter , but with slightly improved performance |
link |
ransac_ground_filter |
A method of removing the ground by approximating the ground to a plane |
link |
Name |
Type |
Description |
~/input/points |
sensor_msgs::msg::PointCloud2 |
reference points |
~/input/indices |
pcl_msgs::msg::Indices |
reference indices |
Output
Name |
Type |
Description |
~/output/points |
sensor_msgs::msg::PointCloud2 |
filtered points |
Parameters
Node Parameters
Name |
Type |
Default Value |
Description |
input_frame |
string |
" " |
input frame id |
output_frame |
string |
" " |
output frame id |
has_static_tf_only |
bool |
false |
flag to listen TF only once |
max_queue_size |
int |
5 |
max queue size of input/output topics |
use_indices |
bool |
false |
flag to use pointcloud indices |
latched_indices |
bool |
false |
flag to latch pointcloud indices |
approximate_sync |
bool |
false |
flag to use approximate sync option |
Ground Segmentation
Name |
Type |
Description |
Default |
Range |
global_slope_max_angle_deg |
float |
global_slope_max_angle_deg |
10 |
N/A |
local_slope_max_angle_deg |
float |
local_slope_max_angle_deg |
13 |
N/A |
split_points_distance_tolerance |
float |
split_points_distance_tolerance |
0.2 |
N/A |
use_virtual_ground_point |
boolean |
use_virtual_ground_point |
1 |
N/A |
split_height_distance |
float |
split_height_distance |
0.2 |
N/A |
non_ground_height_threshold |
float |
non_ground_height_threshold |
0.2 |
N/A |
grid_size_m |
float |
grid_size_m |
0.1 |
N/A |
grid_mode_switch_radius |
float |
grid_mode_switch_radius |
20 |
N/A |
gnd_grid_buffer_size |
integer |
gnd_grid_buffer_size |
4 |
N/A |
detection_range_z_max |
float |
detection_range_z_max |
2.5 |
N/A |
elevation_grid_mode |
boolean |
elevation_grid_mode |
1 |
N/A |
low_priority_region_x |
float |
low_priority_region_x |
-20 |
N/A |
center_pcl_shift |
float |
center_pcl_shift |
0 |
N/A |
radial_divider_angle_deg |
float |
radial_divider_angle_deg |
1 |
N/A |
use_recheck_ground_cluster |
boolean |
use_recheck_ground_cluster |
1 |
N/A |
use_lowest_point |
boolean |
use_lowest_point |
1 |
N/A |
publish_processing_time_detail |
boolean |
publish_processing_time_detail |
0 |
N/A |
RANSAC Ground Filter
Name |
Type |
Description |
Default |
Range |
base_frame |
string |
base_frame |
base_link |
N/A |
unit_axis |
string |
unit_axis |
z |
N/A |
max_iterations |
integer |
max_iterations |
1000 |
N/A |
min_trial |
integer |
min_trial |
5000 |
N/A |
min_points |
integer |
min_points |
1000 |
N/A |
outlier_threshold |
float |
outlier_threshold |
0.01 |
N/A |
plane_slope_threshold |
float |
plane_slope_threshold |
10.0 |
N/A |
voxel_size_x |
float |
voxel_size_x |
0.04 |
N/A |
voxel_size_y |
float |
voxel_size_y |
0.04 |
N/A |
voxel_size_z |
float |
voxel_size_z |
0.04 |
N/A |
height_threshold |
float |
height_threshold |
0.01 |
N/A |
debug |
boolean |
debug |
False |
N/A |
publish_processing_time_detail |
boolean |
publish_processing_time_detail |
False |
N/A |
Ray Ground Filter
Name |
Type |
Description |
Default |
Range |
min_x |
float |
min_x |
-0.01 |
N/A |
max_x |
float |
max_x |
0.01 |
N/A |
min_y |
float |
min_y |
-0.01 |
N/A |
max_y |
float |
max_y |
0.01 |
N/A |
use_vehicle_footprint |
boolean |
use_vehicle_footprint |
0 |
N/A |
general_max_slope |
float |
general_max_slope |
8 |
N/A |
local_max_slope |
float |
local_max_slope |
6 |
N/A |
initial_max_slope |
float |
initial_max_slope |
3 |
N/A |
radial_divider_angle |
float |
radial_divider_angle |
1 |
N/A |
min_height_threshold |
float |
min_height_threshold |
0.15 |
N/A |
concentric_divider_distance |
float |
concentric_divider_distance |
0 |
N/A |
reclass_distance_threshold |
float |
reclass_distance_threshold |
0.1 |
N/A |
publish_processing_time_detail |
boolean |
publish_processing_time_detail |
0 |
N/A |
Scan Ground Filter
Name |
Type |
Description |
Default |
Range |
global_slope_max_angle_deg |
float |
global_slope_max_angle_deg |
10 |
N/A |
local_slope_max_angle_deg |
float |
local_slope_max_angle_deg |
13 |
N/A |
split_points_distance_tolerance |
float |
split_points_distance_tolerance |
0.2 |
N/A |
use_virtual_ground_point |
boolean |
use_virtual_ground_point |
1 |
N/A |
split_height_distance |
float |
split_height_distance |
0.2 |
N/A |
non_ground_height_threshold |
float |
non_ground_height_threshold |
0.2 |
N/A |
grid_size_m |
float |
grid_size_m |
0.1 |
N/A |
grid_mode_switch_radius |
float |
grid_mode_switch_radius |
20 |
N/A |
gnd_grid_buffer_size |
integer |
gnd_grid_buffer_size |
4 |
N/A |
detection_range_z_max |
float |
detection_range_z_max |
2.5 |
N/A |
elevation_grid_mode |
boolean |
elevation_grid_mode |
1 |
N/A |
low_priority_region_x |
float |
low_priority_region_x |
-20 |
N/A |
center_pcl_shift |
float |
center_pcl_shift |
0 |
N/A |
radial_divider_angle_deg |
float |
radial_divider_angle_deg |
1 |
N/A |
use_recheck_ground_cluster |
boolean |
use_recheck_ground_cluster |
1 |
N/A |
use_lowest_point |
boolean |
use_lowest_point |
1 |
N/A |
publish_processing_time_detail |
boolean |
publish_processing_time_detail |
0 |
N/A |
Assumptions / Known limits
autoware::pointcloud_preprocessor::Filter
is implemented based on pcl_perception [1] because of this issue.
References/External links
[1] https://github.com/ros-perception/perception_pcl/blob/ros2/pcl_ros/src/pcl_ros/filters/filter.cpp