From 0dfb6fa3abf681ddc08a42817d544387815a0b3d Mon Sep 17 00:00:00 2001 From: kminoda Date: Thu, 25 Jan 2024 11:53:42 +0900 Subject: [PATCH 1/6] chore(lidar_centerpoint): use config Signed-off-by: kminoda --- .../detector/lidar_dnn_detector.launch.xml | 2 -- .../config/centerpoint.param.yaml | 12 ++++++++++++ .../config/centerpoint_tiny.param.yaml | 12 ++++++++++++ .../launch/lidar_centerpoint.launch.xml | 15 +-------------- .../scripts/lidar_centerpoint_visualizer.py | 2 +- 5 files changed, 26 insertions(+), 17 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml index 1a97659b357d8..0590fc33e80f6 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml @@ -3,7 +3,6 @@ - @@ -17,7 +16,6 @@ - diff --git a/perception/lidar_centerpoint/config/centerpoint.param.yaml b/perception/lidar_centerpoint/config/centerpoint.param.yaml index 0b29a87965b42..d8684f3e2b58f 100644 --- a/perception/lidar_centerpoint/config/centerpoint.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint.param.yaml @@ -13,3 +13,15 @@ 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] + score_threshold: 0.35 + build_only: false # shutdown node after TensorRT engine file is built + has_twist: false + trt_precision: fp16 + densification_num_past_frames: 1 + densification_world_frame_id: map + + # weight files + 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" diff --git a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml index 8252fde8273d8..5eb560dd7be35 100644 --- a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml @@ -13,3 +13,15 @@ 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] + score_threshold: 0.35 + build_only: false # shutdown node after TensorRT engine file is built + has_twist: false + trt_precision: fp16 + densification_num_past_frames: 1 + densification_world_frame_id: map + + # weight files + 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" diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index a7f181ab78ac6..1d0faf2367e9f 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -7,24 +7,11 @@ - - - - - - - - - - - - - - + diff --git a/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py b/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py index 5a1135379615f..177ea050109f1 100755 --- a/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py +++ b/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # Copyright 2022 TIER IV, Inc. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); From d2747e2603b5648412b66a63fa3387800c820c14 Mon Sep 17 00:00:00 2001 From: kminoda Date: Thu, 25 Jan 2024 14:02:54 +0900 Subject: [PATCH 2/6] revert unnecessary fix Signed-off-by: kminoda --- .../lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py b/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py index 177ea050109f1..5a1135379615f 100755 --- a/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py +++ b/perception/lidar_centerpoint/scripts/lidar_centerpoint_visualizer.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python3 +#!/usr/bin/env python # Copyright 2022 TIER IV, Inc. All rights reserved. # # Licensed under the Apache License, Version 2.0 (the "License"); From 1c74fe4c0e973ce7ffc252e319ddbc992aa6ef00 Mon Sep 17 00:00:00 2001 From: kminoda Date: Wed, 31 Jan 2024 09:12:49 +0900 Subject: [PATCH 3/6] fix: revert build_only option Signed-off-by: kminoda --- perception/lidar_centerpoint/config/centerpoint.param.yaml | 1 - .../lidar_centerpoint/config/centerpoint_tiny.param.yaml | 1 - .../lidar_centerpoint/launch/lidar_centerpoint.launch.xml | 4 ++++ 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/perception/lidar_centerpoint/config/centerpoint.param.yaml b/perception/lidar_centerpoint/config/centerpoint.param.yaml index d8684f3e2b58f..a9c3174846d0d 100644 --- a/perception/lidar_centerpoint/config/centerpoint.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint.param.yaml @@ -14,7 +14,6 @@ iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] score_threshold: 0.35 - build_only: false # shutdown node after TensorRT engine file is built has_twist: false trt_precision: fp16 densification_num_past_frames: 1 diff --git a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml index 5eb560dd7be35..474d0e2b695ac 100644 --- a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml @@ -14,7 +14,6 @@ iou_nms_threshold: 0.1 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] score_threshold: 0.35 - build_only: false # shutdown node after TensorRT engine file is built has_twist: false trt_precision: fp16 densification_num_past_frames: 1 diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index 1d0faf2367e9f..eccf8f4a1a882 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -7,11 +7,15 @@ + + + + From b028c8ad909d6ee49a7a27260e3727e6de9f5abd Mon Sep 17 00:00:00 2001 From: kminoda Date: Wed, 31 Jan 2024 09:21:31 +0900 Subject: [PATCH 4/6] docs: update readme Signed-off-by: kminoda --- perception/lidar_centerpoint/README.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/perception/lidar_centerpoint/README.md b/perception/lidar_centerpoint/README.md index f5a15916f31a9..d2cde7ce63fc5 100644 --- a/perception/lidar_centerpoint/README.md +++ b/perception/lidar_centerpoint/README.md @@ -45,6 +45,15 @@ We trained the models using . | `nms_iou_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression | | `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | + +### The `build_only` option + +The `lidar_centerpoint` 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 lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true +``` + ## Assumptions / Known limits - The `object.existence_probability` is stored the value of classification confidence of a DNN, not probability. From 01ebca203c1e62a1d04fa8682a15edf97e7d31aa Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 31 Jan 2024 00:26:47 +0000 Subject: [PATCH 5/6] style(pre-commit): autofix --- perception/lidar_centerpoint/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/lidar_centerpoint/README.md b/perception/lidar_centerpoint/README.md index d2cde7ce63fc5..2a9adedad9074 100644 --- a/perception/lidar_centerpoint/README.md +++ b/perception/lidar_centerpoint/README.md @@ -45,11 +45,11 @@ We trained the models using . | `nms_iou_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression | | `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | - ### The `build_only` option The `lidar_centerpoint` 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 lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true ``` From 118728088dcb810e6ced9d9c896dcbf4af409d6e Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 6 Feb 2024 09:27:28 +0900 Subject: [PATCH 6/6] fix: add pr url Signed-off-by: kminoda --- .../lidar_centerpoint/launch/lidar_centerpoint.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index 06263dd626c89..5489af2c8fb60 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -20,7 +20,7 @@ - + @@ -32,7 +32,7 @@ - +