From dd796bc70b7ff6154fa10438ef0eb6f6af2493b0 Mon Sep 17 00:00:00 2001 From: ismet Date: Mon, 17 Jul 2023 19:11:46 +0300 Subject: [PATCH] add centerpoint params Signed-off-by: ismetatabay --- .../lidar_model/centerpoint.param.yaml | 15 ++++++++ .../lidar_model/centerpoint_tiny.param.yaml | 15 ++++++++ .../detection_class_remapper.param.yaml | 38 +++++++++++++++++++ .../pointpainting.param.yaml | 0 .../tier4_perception_component.launch.xml | 4 +- 5 files changed, 70 insertions(+), 2 deletions(-) create mode 100644 autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml create mode 100644 autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml rename autoware_launch/config/perception/object_recognition/detection/{image_projection_based_fusion => lidar_model}/pointpainting.param.yaml (100%) diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml new file mode 100644 index 0000000000..0b29a87965 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 4 + max_voxel_size: 40000 + point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] + voxel_size: [0.32, 0.32, 10.0] + downsample_factor: 1 + encoder_in_feature_size: 9 + # post-process params + circle_nms_dist_threshold: 0.5 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml new file mode 100644 index 0000000000..8252fde827 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml @@ -0,0 +1,15 @@ +/**: + ros__parameters: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 4 + max_voxel_size: 40000 + point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] + voxel_size: [0.32, 0.32, 10.0] + downsample_factor: 2 + encoder_in_feature_size: 9 + # post-process params + circle_nms_dist_threshold: 0.5 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml new file mode 100644 index 0000000000..ed378ffa44 --- /dev/null +++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml @@ -0,0 +1,38 @@ +/**: + ros__parameters: + allow_remapping_by_area_matrix: + # NOTE(kl): We turn all vehicles into trailers if they go over 3x12 [m^2]. + # NOTE(kl): We turn cars into trucks if they have an area between 2.2 x 5.5 and 3.0 * 12.0 [m^2] + # row: original class. column: class to remap to + #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN + [0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN + 0, 0, 1, 0, 1, 0, 0, 0, #CAR + 0, 0, 0, 0, 1, 0, 0, 0, #TRUCK + 0, 0, 0, 0, 1, 0, 0, 0, #BUS + 0, 0, 0, 0, 0, 0, 0, 0, #TRAILER + 0, 0, 0, 0, 0, 0, 0, 0, #MOTORBIKE + 0, 0, 0, 0, 0, 0, 0, 0, #BICYCLE + 0, 0, 0, 0, 0, 0, 0, 0] #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 + 0.000, 0.000, 12.100, 0.000, 36.000, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 36.000, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN + + + max_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 + 0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE + 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000] #PEDESTRIAN diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/pointpainting.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml similarity index 100% rename from autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/pointpainting.param.yaml rename to autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml diff --git a/autoware_launch/launch/components/tier4_perception_component.launch.xml b/autoware_launch/launch/components/tier4_perception_component.launch.xml index baf29c262b..de5d525ebe 100644 --- a/autoware_launch/launch/components/tier4_perception_component.launch.xml +++ b/autoware_launch/launch/components/tier4_perception_component.launch.xml @@ -44,8 +44,8 @@ value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml" />