Skip to content

Commit

Permalink
chore(lidar_centerpoint): rework parameters (autowarefoundation#6167)
Browse files Browse the repository at this point in the history
* chore(lidar_centerpoint): use config

Signed-off-by: kminoda <[email protected]>

* revert unnecessary fix

Signed-off-by: kminoda <[email protected]>

* fix: revert build_only option

Signed-off-by: kminoda <[email protected]>

* docs: update readme

Signed-off-by: kminoda <[email protected]>

* style(pre-commit): autofix

* fix: add pr url

Signed-off-by: kminoda <[email protected]>

---------

Signed-off-by: kminoda <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Kenzo Lobos Tsunekawa <[email protected]>
  • Loading branch information
3 people authored and zulfaqar-azmi-t4 committed Feb 6, 2024
1 parent 51d4e64 commit d8c3f2a
Show file tree
Hide file tree
Showing 5 changed files with 39 additions and 26 deletions.
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
9 changes: 9 additions & 0 deletions perception/lidar_centerpoint/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,15 @@ We trained the models using <https://github.com/open-mmlab/mmdetection3d>.
| `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.
Expand Down
11 changes: 11 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,14 @@
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
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"
11 changes: 11 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,14 @@
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
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"
32 changes: 8 additions & 24 deletions perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,6 @@
<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"/>

<arg name="use_pointcloud_container" default="false" description="use pointcloud_container"/>
Expand All @@ -19,37 +17,23 @@
<composable_node pkg="lidar_centerpoint" plugin="centerpoint::LidarCenterPointNode" name="lidar_centerpoint">
<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)"/>

<!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 -->
<param name="build_only" value="$(var build_only)"/>
</composable_node>
</load_composable_node>
</group>
<group unless="$(var use_pointcloud_container)">
<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)"/>

<!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 -->
<param name="build_only" value="$(var build_only)"/>
</node>
</group>
</launch>

0 comments on commit d8c3f2a

Please sign in to comment.