Skip to content

Commit 3f9c334

Browse files
kminodapre-commit-ci[bot]
authored andcommitted
chore(image_projection_based_fusion): rework parameters (autowarefoundation#6169)
* chore(image_projection_based_fusion): use config Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * 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 * update component launcher as well 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>
1 parent 585c8c5 commit 3f9c334

5 files changed

+31
-33
lines changed

perception/image_projection_based_fusion/README.md

+9
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,15 @@ The timeout threshold should be set according to the postprocessing time.
5353
E.g, if the postprocessing time is around 50ms, the timeout threshold should be set smaller than 50ms, so that the whole processing time could be less than 100ms.
5454
current default value at autoware.universe for XX1: - timeout_ms: 50.0
5555

56+
#### The `build_only` option
57+
58+
The `pointpainting_fusion` node has `build_only` option to build the TensorRT engine file from the ONNX file.
59+
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:
60+
61+
```bash
62+
ros2 launch image_projection_based_fusion pointpainting_fusion.launch.xml model_name:=pointpainting model_path:=/home/autoware/autoware_data/image_projection_based_fusion model_param_path:=$(ros2 pkg prefix image_projection_based_fusion --share)/config/pointpainting.param.yaml build_only:=true
63+
```
64+
5665
#### Known Limits
5766

5867
The rclcpp::TimerBase timer could not break a for loop, therefore even if time is out when fusing a roi msg at the middle, the program will run until all msgs are fused.

perception/image_projection_based_fusion/config/pointpainting.param.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,11 @@
11
/**:
22
ros__parameters:
3+
trt_precision: fp16
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+
39
model_params:
410
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
511
paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]

perception/image_projection_based_fusion/config/segmentation_pointcloud_fusion.param.yaml

+10
Original file line numberDiff line numberDiff line change
@@ -28,3 +28,13 @@
2828
# this is selected based on semantic segmentation model accuracy,
2929
# calibration accuracy and unknown reaction distance
3030
filter_distance_threshold: 60.0
31+
32+
# debug
33+
debug_mode: false
34+
filter_scope_minx: -100
35+
filter_scope_maxx: 100
36+
filter_scope_miny: -100
37+
filter_scope_maxy: 100
38+
filter_scope_minz: -100
39+
filter_scope_maxz: 100
40+
image_buffer_size: 15

perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml

+6-12
Original file line numberDiff line numberDiff line change
@@ -47,15 +47,12 @@
4747
<composable_node pkg="image_projection_based_fusion" plugin="image_projection_based_fusion::PointPaintingFusionNode" name="pointpainting">
4848
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
4949
<remap from="~/output/objects" to="$(var output/objects)"/>
50-
<param name="trt_precision" value="fp16"/>
51-
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
52-
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
53-
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
54-
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
55-
<param from="$(var model_param_path)"/>
50+
<param from="$(var model_param_path)" allow_substs="true"/>
5651
<param from="$(var sync_param_path)"/>
5752
<param from="$(var class_remapper_param_path)"/>
5853
<param name="rois_number" value="$(var input/rois_number)"/>
54+
55+
<!-- This parameter shall NOT be included in param file. See the PR from the git blame for details. -->
5956
<param name="build_only" value="$(var build_only)"/>
6057

6158
<!-- rois, camera and info -->
@@ -91,15 +88,12 @@
9188
<node pkg="image_projection_based_fusion" exec="pointpainting_fusion_node" name="pointpainting" output="screen">
9289
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
9390
<remap from="~/output/objects" to="$(var output/objects)"/>
94-
<param name="trt_precision" value="fp16"/>
95-
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
96-
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
97-
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
98-
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
99-
<param from="$(var model_param_path)"/>
91+
<param from="$(var model_param_path)" allow_substs="true"/>
10092
<param from="$(var sync_param_path)"/>
10193
<param from="$(var class_remapper_param_path)"/>
10294
<param name="rois_number" value="$(var input/rois_number)"/>
95+
96+
<!-- This parameter shall NOT be included in param file. See the PR from the git blame for details. -->
10397
<param name="build_only" value="$(var build_only)"/>
10498

10599
<!-- rois, camera and info -->

perception/image_projection_based_fusion/launch/segmentation_pointcloud_fusion.launch.xml

-21
Original file line numberDiff line numberDiff line change
@@ -20,17 +20,6 @@
2020
<arg name="output/pointcloud" default="output/pointcloud"/>
2121
<arg name="sync_param_path" default="$(find-pkg-share image_projection_based_fusion)/config/roi_sync.param.yaml"/>
2222
<arg name="semantic_segmentation_based_filter_param_path" default="$(find-pkg-share image_projection_based_fusion)/config/segmentation_pointcloud_fusion.param.yaml"/>
23-
<!-- debug -->
24-
<!-- cspell: ignore minx, maxx, miny, maxy, minz, maxz -->
25-
<arg name="debug_mode" default="false"/>
26-
27-
<arg name="filter_scope_minx" default="-100"/>
28-
<arg name="filter_scope_maxx" default="100"/>
29-
<arg name="filter_scope_miny" default="-100"/>
30-
<arg name="filter_scope_maxy" default="100"/>
31-
<arg name="filter_scope_minz" default="-100"/>
32-
<arg name="filter_scope_maxz" default="100"/>
33-
<arg name="image_buffer_size" default="15"/>
3423
<arg name="input/image0" default="/image_raw0"/>
3524
<arg name="input/image1" default="/image_raw1"/>
3625
<arg name="input/image2" default="/image_raw2"/>
@@ -72,16 +61,6 @@
7261
<param name="input/rois7" value="$(var input/mask7)"/>
7362
<param name="input/camera_info7" value="$(var input/camera_info7)"/>
7463
<param name="input/image7" value="$(var input/image7)"/>
75-
76-
<!-- debug -->
77-
<param name="debug_mode" value="$(var debug_mode)"/>
78-
<param name="filter_scope_minx" value="$(var filter_scope_minx)"/>
79-
<param name="filter_scope_maxx" value="$(var filter_scope_maxx)"/>
80-
<param name="filter_scope_miny" value="$(var filter_scope_miny)"/>
81-
<param name="filter_scope_maxy" value="$(var filter_scope_maxy)"/>
82-
<param name="filter_scope_minz" value="$(var filter_scope_minz)"/>
83-
<param name="filter_scope_maxz" value="$(var filter_scope_maxz)"/>
84-
<param name="image_buffer_size" value="$(var image_buffer_size)"/>
8564
</node>
8665
</group>
8766
</launch>

0 commit comments

Comments
 (0)