Skip to content

Commit 44c6169

Browse files
authored
fix(lidar_centerpoint): add param file for centerpoint_tiny (#6901)
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 46905ee commit 44c6169

File tree

3 files changed

+21
-2
lines changed

3 files changed

+21
-2
lines changed

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
<arg name="output/objects" value="objects"/>
1919
<arg name="model_name" value="$(var centerpoint_model_name)"/>
2020
<arg name="model_path" value="$(var centerpoint_model_path)"/>
21-
<arg name="model_param_path" value="$(var lidar_model_param_path)/centerpoint.param.yaml"/>
21+
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var centerpoint_model_name).param.yaml"/>
2222
<arg name="ml_package_param_path" value="$(var centerpoint_model_path)/$(var centerpoint_model_name)_ml_package.param.yaml"/>
2323
<arg name="class_remapper_param_path" value="$(var centerpoint_model_path)/detection_class_remapper.param.yaml"/>
2424

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
/**:
2+
ros__parameters:
3+
# weight files
4+
encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
5+
encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
6+
head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
7+
head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
8+
trt_precision: fp16
9+
post_process_params:
10+
# post-process params
11+
circle_nms_dist_threshold: 0.5
12+
iou_nms_target_class_names: ["CAR"]
13+
iou_nms_search_distance_2d: 10.0
14+
iou_nms_threshold: 0.1
15+
score_threshold: 0.35
16+
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
17+
densification_params:
18+
world_frame_id: map
19+
num_past_frames: 1

perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
66
<arg name="model_name" default="centerpoint_tiny" description="options: `centerpoint` or `centerpoint_tiny`"/>
77
<arg name="model_path" default="$(var data_path)/lidar_centerpoint"/>
8-
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/centerpoint.param.yaml"/>
8+
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml"/>
99
<arg name="ml_package_param_path" default="$(var model_path)/$(var model_name)_ml_package.param.yaml"/>
1010
<arg name="class_remapper_param_path" default="$(var model_path)/detection_class_remapper.param.yaml"/>
1111
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>

0 commit comments

Comments
 (0)