Skip to content

Commit 37343a6

Browse files
kminodapre-commit-ci[bot]knzo25
authored
chore(lidar_centerpoint): rework parameters (#6167)
* chore(lidar_centerpoint): use config Signed-off-by: kminoda <koji.minoda@tier4.jp> * revert unnecessary fix Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix: revert build_only option Signed-off-by: kminoda <koji.minoda@tier4.jp> * docs: update readme Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * fix: add pr url Signed-off-by: kminoda <koji.minoda@tier4.jp> --------- Signed-off-by: kminoda <koji.minoda@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>
1 parent d4441bd commit 37343a6

File tree

5 files changed

+39
-26
lines changed

5 files changed

+39
-26
lines changed

launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml

-2
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
<!-- Lidar parameters -->
44
<arg name="input/pointcloud"/>
55
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `clustering`"/>
6-
<arg name="lidar_detection_score_threshold" default="0.35"/>
76

87
<!-- Lidar detector centerpoint parameters -->
98
<arg name="centerpoint_model_name" default="centerpoint_tiny"/>
@@ -17,7 +16,6 @@
1716
<include file="$(find-pkg-share lidar_centerpoint)/launch/lidar_centerpoint.launch.xml">
1817
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
1918
<arg name="output/objects" value="objects"/>
20-
<arg name="score_threshold" value="$(var lidar_detection_score_threshold)"/>
2119
<arg name="model_name" value="$(var centerpoint_model_name)"/>
2220
<arg name="model_path" value="$(var centerpoint_model_path)"/>
2321
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var centerpoint_model_name).param.yaml"/>

perception/lidar_centerpoint/README.md

+9
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,15 @@ We trained the models using <https://github.com/open-mmlab/mmdetection3d>.
4545
| `nms_iou_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression |
4646
| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built |
4747

48+
### The `build_only` option
49+
50+
The `lidar_centerpoint` node has `build_only` option to build the TensorRT engine file from the ONNX file.
51+
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:
52+
53+
```bash
54+
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
55+
```
56+
4857
## Assumptions / Known limits
4958

5059
- The `object.existence_probability` is stored the value of classification confidence of a DNN, not probability.

perception/lidar_centerpoint/config/centerpoint.param.yaml

+11
Original file line numberDiff line numberDiff line change
@@ -13,3 +13,14 @@
1313
iou_nms_search_distance_2d: 10.0
1414
iou_nms_threshold: 0.1
1515
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
16+
score_threshold: 0.35
17+
has_twist: false
18+
trt_precision: fp16
19+
densification_num_past_frames: 1
20+
densification_world_frame_id: map
21+
22+
# weight files
23+
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
24+
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
25+
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
26+
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"

perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml

+11
Original file line numberDiff line numberDiff line change
@@ -13,3 +13,14 @@
1313
iou_nms_search_distance_2d: 10.0
1414
iou_nms_threshold: 0.1
1515
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
16+
score_threshold: 0.35
17+
has_twist: false
18+
trt_precision: fp16
19+
densification_num_past_frames: 1
20+
densification_world_frame_id: map
21+
22+
# weight files
23+
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
24+
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
25+
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
26+
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"

perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml

+8-24
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,6 @@
77
<arg name="model_path" default="$(var data_path)/lidar_centerpoint"/>
88
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml"/>
99
<arg name="class_remapper_param_path" default="$(find-pkg-share lidar_centerpoint)/config/detection_class_remapper.param.yaml"/>
10-
<arg name="score_threshold" default="0.35"/>
11-
<arg name="has_twist" default="false"/>
1210
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
1311

1412
<arg name="use_pointcloud_container" default="false" description="use pointcloud_container"/>
@@ -19,37 +17,23 @@
1917
<composable_node pkg="lidar_centerpoint" plugin="centerpoint::LidarCenterPointNode" name="lidar_centerpoint">
2018
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
2119
<remap from="~/output/objects" to="$(var output/objects)"/>
22-
<param name="score_threshold" value="$(var score_threshold)"/>
23-
<param name="densification_world_frame_id" value="map"/>
24-
<param name="densification_num_past_frames" value="1"/>
25-
<param name="trt_precision" value="fp16"/>
26-
<param name="has_twist" value="$(var has_twist)"/>
27-
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
28-
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
29-
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
30-
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
31-
<param name="build_only" value="$(var build_only)"/>
32-
<param from="$(var model_param_path)"/>
20+
<param from="$(var model_param_path)" allow_substs="true"/>
3321
<param from="$(var class_remapper_param_path)"/>
22+
23+
<!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 -->
24+
<param name="build_only" value="$(var build_only)"/>
3425
</composable_node>
3526
</load_composable_node>
3627
</group>
3728
<group unless="$(var use_pointcloud_container)">
3829
<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
3930
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
4031
<remap from="~/output/objects" to="$(var output/objects)"/>
41-
<param name="score_threshold" value="$(var score_threshold)"/>
42-
<param name="densification_world_frame_id" value="map"/>
43-
<param name="densification_num_past_frames" value="1"/>
44-
<param name="trt_precision" value="fp16"/>
45-
<param name="has_twist" value="$(var has_twist)"/>
46-
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
47-
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
48-
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
49-
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
50-
<param name="build_only" value="$(var build_only)"/>
51-
<param from="$(var model_param_path)"/>
32+
<param from="$(var model_param_path)" allow_substs="true"/>
5233
<param from="$(var class_remapper_param_path)"/>
34+
35+
<!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 -->
36+
<param name="build_only" value="$(var build_only)"/>
5337
</node>
5438
</group>
5539
</launch>

0 commit comments

Comments
 (0)