Skip to content

Commit

Permalink
Merge pull request #1160 from tier4/hotfix/beta/v0.20.1.1+parameter_r…
Browse files Browse the repository at this point in the history
…ework

chore(image_projection_based_fusion): rework parameters (autowarefoundation#6169)
  • Loading branch information
shmpwk authored Feb 27, 2024
2 parents fe604a9 + e7ae1c1 commit fb3c149
Show file tree
Hide file tree
Showing 5 changed files with 31 additions and 33 deletions.
9 changes: 9 additions & 0 deletions perception/image_projection_based_fusion/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,15 @@ The timeout threshold should be set according to the postprocessing time.
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.
current default value at autoware.universe for XX1: - timeout_ms: 50.0

#### The `build_only` option

The `pointpainting_fusion` 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 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
```

#### Known Limits

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.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,11 @@
/**:
ros__parameters:
trt_precision: fp16
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"

model_params:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,3 +28,13 @@
# this is selected based on semantic segmentation model accuracy,
# calibration accuracy and unknown reaction distance
filter_distance_threshold: 60.0

# debug
debug_mode: false
filter_scope_minx: -100
filter_scope_maxx: 100
filter_scope_miny: -100
filter_scope_maxy: 100
filter_scope_minz: -100
filter_scope_maxz: 100
image_buffer_size: 15
Original file line number Diff line number Diff line change
Expand Up @@ -47,15 +47,12 @@
<composable_node pkg="image_projection_based_fusion" plugin="image_projection_based_fusion::PointPaintingFusionNode" name="pointpainting">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param name="trt_precision" value="fp16"/>
<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 from="$(var model_param_path)"/>
<param from="$(var model_param_path)" allow_substs="true"/>
<param from="$(var sync_param_path)"/>
<param from="$(var class_remapper_param_path)"/>
<param name="rois_number" value="$(var input/rois_number)"/>

<!-- This parameter shall NOT be included in param file. See the PR from the git blame for details. -->
<param name="build_only" value="$(var build_only)"/>

<!-- rois, camera and info -->
Expand Down Expand Up @@ -91,15 +88,12 @@
<node pkg="image_projection_based_fusion" exec="pointpainting_fusion_node" name="pointpainting" output="screen">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param name="trt_precision" value="fp16"/>
<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 from="$(var model_param_path)"/>
<param from="$(var model_param_path)" allow_substs="true"/>
<param from="$(var sync_param_path)"/>
<param from="$(var class_remapper_param_path)"/>
<param name="rois_number" value="$(var input/rois_number)"/>

<!-- This parameter shall NOT be included in param file. See the PR from the git blame for details. -->
<param name="build_only" value="$(var build_only)"/>

<!-- rois, camera and info -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,17 +20,6 @@
<arg name="output/pointcloud" default="output/pointcloud"/>
<arg name="sync_param_path" default="$(find-pkg-share image_projection_based_fusion)/config/roi_sync.param.yaml"/>
<arg name="semantic_segmentation_based_filter_param_path" default="$(find-pkg-share image_projection_based_fusion)/config/segmentation_pointcloud_fusion.param.yaml"/>
<!-- debug -->
<!-- cspell: ignore minx, maxx, miny, maxy, minz, maxz -->
<arg name="debug_mode" default="false"/>

<arg name="filter_scope_minx" default="-100"/>
<arg name="filter_scope_maxx" default="100"/>
<arg name="filter_scope_miny" default="-100"/>
<arg name="filter_scope_maxy" default="100"/>
<arg name="filter_scope_minz" default="-100"/>
<arg name="filter_scope_maxz" default="100"/>
<arg name="image_buffer_size" default="15"/>
<arg name="input/image0" default="/image_raw0"/>
<arg name="input/image1" default="/image_raw1"/>
<arg name="input/image2" default="/image_raw2"/>
Expand Down Expand Up @@ -72,16 +61,6 @@
<param name="input/rois7" value="$(var input/mask7)"/>
<param name="input/camera_info7" value="$(var input/camera_info7)"/>
<param name="input/image7" value="$(var input/image7)"/>

<!-- debug -->
<param name="debug_mode" value="$(var debug_mode)"/>
<param name="filter_scope_minx" value="$(var filter_scope_minx)"/>
<param name="filter_scope_maxx" value="$(var filter_scope_maxx)"/>
<param name="filter_scope_miny" value="$(var filter_scope_miny)"/>
<param name="filter_scope_maxy" value="$(var filter_scope_maxy)"/>
<param name="filter_scope_minz" value="$(var filter_scope_minz)"/>
<param name="filter_scope_maxz" value="$(var filter_scope_maxz)"/>
<param name="image_buffer_size" value="$(var image_buffer_size)"/>
</node>
</group>
</launch>

0 comments on commit fb3c149

Please sign in to comment.