Skip to content

Commit

Permalink
fix(pointpainting): fix pointpainting and centerpoint path (autowaref…
Browse files Browse the repository at this point in the history
…oundation#890)

* fix_pointpainting_path

Signed-off-by: Yuxuan Liu <[email protected]>

* style(pre-commit): autofix

* merge

Signed-off-by: Yuxuan Liu <[email protected]>

* add centerpoint_xx1 param

Signed-off-by: Yuxuan Liu <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: Yuxuan Liu <[email protected]>
Co-authored-by: Yuxuan Liu <[email protected]>
Co-authored-by: Owen-Liuyuxuan <[email protected]>
  • Loading branch information
3 people authored Jun 27, 2024
1 parent a017f6a commit 4e1b8c7
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 2 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
/**:
ros__parameters:

# 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"
trt_precision: fp16
post_process_params:
# post-process params
circle_nms_dist_threshold: 0.5
iou_nms_target_class_names: ["CAR"]
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
densification_params:
world_frame_id: map
num_past_frames: 1
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
<arg name="input/pointcloud" value="/sensing/lidar/concatenated/pointcloud"/>
<arg name="use_traffic_light_recognition" value="$(var use_traffic_light_recognition)"/>
<arg name="lidar_detection_model" value="$(var lidar_detection_model)"/>
<arg name="object_recognition_detection_lidar_model_param_path" value="/opt/autoware/mlmodels/$(var lidar_detection_model)"/>
<arg name="pointpainting_model_path" value="/opt/autoware/mlmodels/pointpainting"/>
<arg name="centerpoint_model_name" value="centerpoint_xx1"/>
<arg name="centerpoint_model_path" value="/opt/autoware/mlmodels/$(var lidar_detection_model)"/>
<arg name="traffic_light_recognition/fusion_only" value="$(var traffic_light_recognition/fusion_only)"/>
Expand Down Expand Up @@ -112,7 +112,7 @@
name="object_recognition_detection_radar_object_clustering_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/clustering/radar_object_clustering.param.yaml"
/>
<!-- <arg name="object_recognition_detection_lidar_model_param_path" value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/lidar_model"/> -->
<arg name="object_recognition_detection_lidar_model_param_path" value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/lidar_model"/>
<arg
name="object_recognition_detection_object_velocity_splitter_radar_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/detection/object_velocity_splitter/object_velocity_splitter_radar.param.yaml"
Expand Down

0 comments on commit 4e1b8c7

Please sign in to comment.