Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore(lidar_centerpoint): rework parameters #6167

Merged
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
<!-- Lidar parameters -->
<arg name="input/pointcloud"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `clustering`"/>
<arg name="lidar_detection_score_threshold" default="0.35"/>

<!-- Lidar detector centerpoint parameters -->
<arg name="centerpoint_model_name" default="centerpoint_tiny"/>
Expand All @@ -17,7 +16,6 @@
<include file="$(find-pkg-share lidar_centerpoint)/launch/lidar_centerpoint.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="output/objects" value="objects"/>
<arg name="score_threshold" value="$(var lidar_detection_score_threshold)"/>
<arg name="model_name" value="$(var centerpoint_model_name)"/>
<arg name="model_path" value="$(var centerpoint_model_path)"/>
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var centerpoint_model_name).param.yaml"/>
Expand Down
12 changes: 12 additions & 0 deletions perception/lidar_centerpoint/config/centerpoint.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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"
12 changes: 12 additions & 0 deletions perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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"
15 changes: 1 addition & 14 deletions perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,24 +7,11 @@
<arg name="model_path" default="$(var data_path)/lidar_centerpoint"/>
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml"/>
<arg name="class_remapper_param_path" default="$(find-pkg-share lidar_centerpoint)/config/detection_class_remapper.param.yaml"/>
<arg name="score_threshold" default="0.35"/>
<arg name="has_twist" default="false"/>
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
miursh marked this conversation as resolved.
Show resolved Hide resolved

<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param name="score_threshold" value="$(var score_threshold)"/>
<param name="densification_world_frame_id" value="map"/>
<param name="densification_num_past_frames" value="1"/>
<param name="trt_precision" value="fp16"/>
<param name="has_twist" value="$(var has_twist)"/>
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
<param name="build_only" value="$(var build_only)"/>
<param from="$(var model_param_path)"/>
<param from="$(var model_param_path)" allow_substs="true"/>
<param from="$(var class_remapper_param_path)"/>
</node>
</launch>
Loading