Skip to content

Commit

Permalink
Merge pull request autowarefoundation#617 from tier4/cherry-pick/pr83…
Browse files Browse the repository at this point in the history
…1+946

chore(ground_segmentation): cherry pick/pr831+946 and fix params
  • Loading branch information
0x126 authored Apr 19, 2024
2 parents 6cf7d23 + 645b910 commit bc0433b
Showing 1 changed file with 55 additions and 14 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/**:
ros__parameters:
additional_lidars: ["front_lower"]
additional_lidars: ["front_lower","left_upper"]
ransac_input_topics: []
use_single_frame_filter: False
use_time_series_filter: True
Expand All @@ -20,16 +20,20 @@
parameters:
global_slope_max_angle_deg: 10.0
local_slope_max_angle_deg: 25.0 # recommended 30.0 for non elevation_grid_mode
split_points_distance_tolerance: 0.15
split_points_distance_tolerance: 0.2
use_virtual_ground_point: True
split_height_distance: 0.2
non_ground_height_threshold: 0.12
non_ground_height_threshold: 0.1
grid_size_m: 0.2
grid_mode_switch_radius: 20.0
gnd_grid_buffer_size: 5
detection_range_z_max: 3.2
elevation_grid_mode: true
use_recheck_ground_cluster: true
use_lowest_point: false
low_priority_region_x: -20.0
center_pcl_shift: 0.0
radial_divider_angle_deg: 1.0

# common_ground_filter:
# plugin: "ground_segmentation::RayGroundFilterComponent"
Expand Down Expand Up @@ -61,8 +65,12 @@
grid_mode_switch_radius: 20.0
gnd_grid_buffer_size: 4
detection_range_z_max: 3.2
center_pcl_shift: 0.0
elevation_grid_mode: true
use_recheck_ground_cluster: true
use_lowest_point: true
low_priority_region_x: -20.0
center_pcl_shift: 0.0
radial_divider_angle_deg: 1.0

front_lower_crop_box_filter:
parameters:
Expand All @@ -77,16 +85,49 @@
front_lower_ground_filter:
plugin: "ground_segmentation::ScanGroundFilterComponent"
parameters:
global_slope_max_angle_deg: 10.0
local_slope_max_angle_deg: 18.0 # recommended 30.0 for non elevation_grid_mode
split_points_distance_tolerance: 0.10 # recommended 0.1 for non elevation_grid_mode
split_height_distance: 0.05 # recommended 0.05 for non elevation_grid_mode
use_virtual_ground_point: true
non_ground_height_threshold: 0.1
grid_size_m: 0.1
grid_mode_switch_radius: 20.0
global_slope_max_angle_deg: 5.0
local_slope_max_angle_deg: 5.0 # recommended 30.0 for non elevation_grid_mode
split_points_distance_tolerance: 0.20 # recommended 0.045 for non elevation_grid_mode
split_height_distance: 0.2 # recommended 0.15 for non elevation_grid_mode
use_virtual_ground_point: False
non_ground_height_threshold: 0.05
grid_size_m: 0.2
grid_mode_switch_radius: 10.0
gnd_grid_buffer_size: 4
detection_range_z_max: 3.2
elevation_grid_mode: true
use_recheck_ground_cluster: true
use_lowest_point: true
low_priority_region_x: -20.0
center_pcl_shift: 0.0
radial_divider_angle_deg: 1.0

left_upper_crop_box_filter:
parameters:
min_x: -0.0
max_x: 40.0
min_y: -10.0
max_y: 10.0
max_z: 1. # recommended 2.5 for non elevation_grid_mode
min_z: -1.0 # recommended 0.0 for non elevation_grid_mode
negative: False

left_upper_ground_filter:
plugin: "ground_segmentation::ScanGroundFilterComponent"
parameters:
global_slope_max_angle_deg: 6.0
local_slope_max_angle_deg: 6.0 # recommended 30.0 for non elevation_grid_mode
split_points_distance_tolerance: 0.20 # recommended 0.045 for non elevation_grid_mode
split_height_distance: 0.2 # recommended 0.15 for non elevation_grid_mode
use_virtual_ground_point: False
non_ground_height_threshold: 0.05
grid_size_m: 0.2
grid_mode_switch_radius: 10.0
gnd_grid_buffer_size: 3
detection_range_z_max: 3.2
elevation_grid_mode: true
use_recheck_ground_cluster: true
use_lowest_point: true
low_priority_region_x: -20.0
center_pcl_shift: 0.0
elevation_grid_mode: false
use_recheck_ground_cluster: false
radial_divider_angle_deg: 1.0

0 comments on commit bc0433b

Please sign in to comment.