From 13aa41e550387123a4d81a17e5b0c2ae0dca11f3 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 21 Dec 2022 17:03:14 +0900 Subject: [PATCH] feat(autoware_launch): move config from autoware.universe for perception (#131) feat(autoware_launch): move config to autoware_launch for perception Signed-off-by: kminoda Signed-off-by: kminoda --- .../object_lanelet_filter.param.yaml | 11 ++++ .../object_position_filter.param.yaml | 16 +++++ .../pointcloud_map_filter.param.yaml | 5 ++ .../data_association_matrix.param.yaml | 66 +++++++++++++++++++ .../elevation_map_parameters.yaml | 30 +++++++++ .../ground_segmentation.param.yaml | 31 +++++++++ autoware_launch/launch/autoware.launch.xml | 2 +- .../tier4_perception_component.launch.xml | 41 ++++++++++++ 8 files changed, 201 insertions(+), 1 deletion(-) create mode 100644 autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml create mode 100644 autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml create mode 100644 autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml create mode 100644 autoware_launch/launch/components/tier4_perception_component.launch.xml diff --git a/autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml new file mode 100644 index 0000000000..dfdee95642 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/object_lanelet_filter.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + filter_target_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + TRAILER : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false diff --git a/autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml new file mode 100644 index 0000000000..70afd9d31b --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/object_position_filter.param.yaml @@ -0,0 +1,16 @@ +/**: + ros__parameters: + filter_target_label: + UNKNOWN : true + CAR : false + TRUCK : false + BUS : false + TRAILER : false + MOTORCYCLE : false + BICYCLE : false + PEDESTRIAN : false + + upper_bound_x: 100.0 + lower_bound_x: 0.0 + upper_bound_y: 10.0 + lower_bound_y: -10.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml b/autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml new file mode 100644 index 0000000000..a07a9416c2 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/pointcloud_map_filter.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + use_down_sample_filter: False + down_sample_voxel_size: 0.1 + distance_threshold: 0.5 diff --git a/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml new file mode 100644 index 0000000000..2541ab0367 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.param.yaml @@ -0,0 +1,66 @@ +/**: + ros__parameters: + can_assign_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN <-Measurement + [1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN <-Tracker + 0, 1, 1, 1, 1, 0, 0, 0, #CAR + 0, 1, 1, 1, 1, 0, 0, 0, #TRUCK + 0, 1, 1, 1, 1, 0, 0, 0, #BUS + 0, 1, 1, 1, 1, 0, 0, 0, #TRAILER + 0, 0, 0, 0, 0, 1, 1, 1, #MOTORBIKE + 0, 0, 0, 0, 0, 1, 1, 1, #BICYCLE + 0, 0, 0, 0, 0, 1, 1, 1] #PEDESTRIAN + + max_dist_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [4.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, #UNKNOWN + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #CAR + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRUCK + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #BUS + 4.0, 2.0, 5.0, 5.0, 5.0, 1.0, 1.0, 1.0, #TRAILER + 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #MOTORBIKE + 3.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0, #BICYCLE + 2.0, 1.0, 1.0, 1.0, 1.0, 3.0, 3.0, 2.0] #PEDESTRIAN + max_area_matrix: + # NOTE: The size of truck is 12 m length x 3 m width. + # NOTE: The size of trailer is 20 m length x 3 m width. + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, 100.00, #UNKNOWN + 12.10, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #CAR + 36.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRUCK + 60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #BUS + 60.00, 12.10, 36.00, 60.00, 60.00, 10000.00, 10000.00, 10000.00, #TRAILER + 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #MOTORBIKE + 2.50, 10000.00, 10000.00, 10000.00, 10000.00, 2.50, 2.50, 1.00, #BICYCLE + 2.00, 10000.00, 10000.00, 10000.00, 10000.00, 1.50, 1.50, 1.00] #PEDESTRIAN + min_area_matrix: + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN + 3.600, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #CAR + 6.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRUCK + 10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #BUS + 10.000, 3.600, 6.000, 10.000, 10.000, 0.000, 0.000, 0.000, #TRAILER + 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #MOTORBIKE + 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100, #BICYCLE + 0.001, 0.000, 0.000, 0.000, 0.000, 0.100, 0.100, 0.100] #PEDESTRIAN + max_rad_matrix: # If value is greater than pi, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, TRAILER MOTORBIKE, BICYCLE, PEDESTRIAN + [3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #UNKNOWN + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #CAR + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRUCK + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #BUS + 3.150, 1.047, 1.047, 1.047, 1.047, 3.150, 3.150, 3.150, #TRAILER + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #MOTORBIKE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, #BICYCLE + 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150, 3.150] #PEDESTRIAN + + min_iou_matrix: # If value is negative, it will be ignored. + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN + [0.0001, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #UNKNOWN + 0.1, 0.1, 0.2, 0.2, 0.2, 0.1, 0.1, 0.1, #CAR + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRUCK + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #BUS + 0.1, 0.2, 0.3, 0.3, 0.3, 0.1, 0.1, 0.1, #TRAILER + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #MOTORBIKE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, #BICYCLE + 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.0001] #PEDESTRIAN diff --git a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml new file mode 100644 index 0000000000..781ccb806b --- /dev/null +++ b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/elevation_map_parameters.yaml @@ -0,0 +1,30 @@ +pcl_grid_map_extraction: + num_processing_threads: 12 + cloud_transform: + translation: + x: 0.0 + y: 0.0 + z: 0.0 + rotation: # intrinsic rotation X-Y-Z (r-p-y)sequence + r: 0.0 + p: 0.0 + y: 0.0 + cluster_extraction: + cluster_tolerance: 0.2 + min_num_points: 3 + max_num_points: 1000000 + outlier_removal: + is_remove_outliers: false + mean_K: 10 + stddev_threshold: 1.0 + downsampling: + is_downsample_cloud: false + voxel_size: + x: 0.02 + y: 0.02 + z: 0.02 + grid_map: + min_num_points_per_cell: 3 + resolution: 0.3 + height_type: 1 + height_thresh: 1.0 diff --git a/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml new file mode 100644 index 0000000000..8d56e12244 --- /dev/null +++ b/autoware_launch/config/perception/obstacle_segmentation/ground_segmentation/ground_segmentation.param.yaml @@ -0,0 +1,31 @@ +/**: + ros__parameters: + additional_lidars: [] + ransac_input_topics: [] + use_single_frame_filter: False + use_time_series_filter: True + + common_crop_box_filter: + parameters: + min_x: -50.0 + max_x: 100.0 + min_y: -50.0 + max_y: 50.0 + max_z: 2.5 # recommended 2.5 for non elevation_grid_mode + min_z: -2.5 # recommended 0.0 for non elevation_grid_mode + negative: False + + common_ground_filter: + plugin: "ground_segmentation::ScanGroundFilterComponent" + parameters: + global_slope_max_angle_deg: 10.0 + local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode + split_points_distance_tolerance: 0.2 + use_virtual_ground_point: True + split_height_distance: 0.2 + non_ground_height_threshold: 0.20 + grid_size_m: 0.1 + grid_mode_switch_radius: 20.0 + gnd_grid_buffer_size: 4 + detection_range_z_max: 2.5 + elevation_grid_mode: true diff --git a/autoware_launch/launch/autoware.launch.xml b/autoware_launch/launch/autoware.launch.xml index 01d1b45a45..8f84b56d8a 100644 --- a/autoware_launch/launch/autoware.launch.xml +++ b/autoware_launch/launch/autoware.launch.xml @@ -101,7 +101,7 @@ - + diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml new file mode 100644 index 0000000000..9d963a0c3d --- /dev/null +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + +