From 595d4402d7f58ecb16fac956bd08ae76801ee755 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 10 Jan 2024 10:40:08 +0900 Subject: [PATCH] fix(pointpainting): update parameter structure (#778) * fix(pointpainting): update parameter structure Signed-off-by: kminoda * update roi_sync.param.yaml Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../roi_sync.param.yaml | 2 + .../lidar_model/pointpainting.param.yaml | 40 +++++++++++-------- 2 files changed, 26 insertions(+), 16 deletions(-) diff --git a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml index 0e4c52ba92..99d85089be 100644 --- a/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/image_projection_based_fusion/roi_sync.param.yaml @@ -3,6 +3,8 @@ input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] timeout_ms: 70.0 match_threshold_ms: 50.0 + image_buffer_size: 15 + debug_mode: false filter_scope_min_x: -100.0 filter_scope_min_y: -100.0 filter_scope_min_z: -100.0 diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml index e1be5426cb..21d31f2163 100755 --- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/pointpainting.param.yaml @@ -1,18 +1,26 @@ /**: ros__parameters: - class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] - paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] - point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle - max_voxel_size: 40000 - point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] - voxel_size: [0.32, 0.32, 8.0] - downsample_factor: 1 - encoder_in_feature_size: 12 - yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] - # post-process params - circle_nms_dist_threshold: 0.3 - iou_nms_target_class_names: ["CAR"] - iou_nms_search_distance_2d: 10.0 - iou_nms_threshold: 0.1 - # omp params - omp_num_threads: 1 + model_params: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle + max_voxel_size: 40000 + point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + voxel_size: [0.32, 0.32, 8.0] + downsample_factor: 1 + encoder_in_feature_size: 12 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + has_twist: false + densification_params: + world_frame_id: "map" + num_past_frames: 0 + post_process_params: + # post-process params + circle_nms_dist_threshold: 0.3 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + score_threshold: 0.4 + omp_params: + # omp params + num_threads: 1