From e7ae1c1f8da5695b48765c9948ed3a6442857a97 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Fri, 2 Feb 2024 08:18:58 +0900 Subject: [PATCH] chore(image_projection_based_fusion): rework parameters (#6169) * chore(image_projection_based_fusion): use config Signed-off-by: kminoda * style(pre-commit): autofix * fix: revert build_only option Signed-off-by: kminoda * docs: update readme Signed-off-by: kminoda * style(pre-commit): autofix * update component launcher as well Signed-off-by: kminoda --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../image_projection_based_fusion/README.md | 9 ++++++++ .../config/pointpainting.param.yaml | 6 ++++++ .../segmentation_pointcloud_fusion.param.yaml | 10 +++++++++ .../launch/pointpainting_fusion.launch.xml | 18 ++++++---------- .../segmentation_pointcloud_fusion.launch.xml | 21 ------------------- 5 files changed, 31 insertions(+), 33 deletions(-) diff --git a/perception/image_projection_based_fusion/README.md b/perception/image_projection_based_fusion/README.md index dba64a27232b1..e83cf92400a60 100644 --- a/perception/image_projection_based_fusion/README.md +++ b/perception/image_projection_based_fusion/README.md @@ -53,6 +53,15 @@ The timeout threshold should be set according to the postprocessing time. E.g, if the postprocessing time is around 50ms, the timeout threshold should be set smaller than 50ms, so that the whole processing time could be less than 100ms. current default value at autoware.universe for XX1: - timeout_ms: 50.0 +#### The `build_only` option + +The `pointpainting_fusion` node has `build_only` option to build the TensorRT engine file from the ONNX file. +Although it is preferred to move all the ROS parameters in `.param.yaml` file in Autoware Universe, the `build_only` option is not moved to the `.param.yaml` file for now, because it may be used as a flag to execute the build as a pre-task. You can execute with the following command: + +```bash +ros2 launch image_projection_based_fusion pointpainting_fusion.launch.xml model_name:=pointpainting model_path:=/home/autoware/autoware_data/image_projection_based_fusion model_param_path:=$(ros2 pkg prefix image_projection_based_fusion --share)/config/pointpainting.param.yaml build_only:=true +``` + #### Known Limits The rclcpp::TimerBase timer could not break a for loop, therefore even if time is out when fusing a roi msg at the middle, the program will run until all msgs are fused. diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml index 21d31f216373b..8ccd46978630d 100755 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -1,5 +1,11 @@ /**: ros__parameters: + trt_precision: fp16 + encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx" + encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine" + head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx" + head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine" + model_params: class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] diff --git a/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml index 914ad13519807..c2752710a54f1 100644 --- a/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml +++ b/perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml @@ -28,3 +28,13 @@ # this is selected based on semantic segmentation model accuracy, # calibration accuracy and unknown reaction distance filter_distance_threshold: 60.0 + + # debug + debug_mode: false + filter_scope_minx: -100 + filter_scope_maxx: 100 + filter_scope_miny: -100 + filter_scope_maxy: 100 + filter_scope_minz: -100 + filter_scope_maxz: 100 + image_buffer_size: 15 diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index db13d73e37fa7..f336eb16e94a1 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -47,15 +47,12 @@ - - - - - - + + + @@ -91,15 +88,12 @@ - - - - - - + + + diff --git a/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml index 96bf47594bfe8..1db2bb20793ac 100644 --- a/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml @@ -20,17 +20,6 @@ - - - - - - - - - - - @@ -72,16 +61,6 @@ - - - - - - - - - -