Skip to content

Commit 742f44a

Browse files
kminodapre-commit-ci[bot]miurshknzo25
authored
feat(detection): add container option (#6228)
* feat(lidar_centerpoint,image_projection_based_fusion): add pointcloud_container option Signed-off-by: kminoda <koji.minoda@tier4.jp> * revert lidar_perception_model Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * fix: add options Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix: fix default param Signed-off-by: kminoda <koji.minoda@tier4.jp> * update node name Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix: fix IfCondition Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix pointpainting namespace Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix: fix launch args Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix(euclidean_cluster): do not launch individual container when use_pointcloud_container is true Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix(euclidean_cluster): fix launch condition Signed-off-by: kminoda <koji.minoda@tier4.jp> * fix(euclidean_cluster): fix launch condition Signed-off-by: kminoda <koji.minoda@tier4.jp> * Update perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --------- Signed-off-by: kminoda <koji.minoda@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>
1 parent 9687a49 commit 742f44a

10 files changed

+135
-24
lines changed

launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml

+3
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,9 @@
8585
<arg name="model_path" value="$(var pointpainting_model_path)"/>
8686
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var lidar_detection_model).param.yaml"/>
8787
<arg name="class_remapper_param_path" value="$(var lidar_model_param_path)/detection_class_remapper.param.yaml"/>
88+
89+
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
90+
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
8891
</include>
8992
</group>
9093

launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml

+3
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,9 @@
2222
<arg name="model_path" value="$(var centerpoint_model_path)"/>
2323
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var centerpoint_model_name).param.yaml"/>
2424
<arg name="class_remapper_param_path" value="$(var lidar_model_param_path)/detection_class_remapper.param.yaml"/>
25+
26+
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
27+
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
2528
</include>
2629
</group>
2730
</group>

launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml

+3
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,9 @@
2626
<arg name="input_pointcloud" value="/perception/object_recognition/detection/pointcloud_map_filtered/pointcloud"/>
2727
<arg name="output_clusters" value="clusters"/>
2828
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
29+
30+
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
31+
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
2932
</include>
3033
</group>
3134

perception/euclidean_cluster/launch/euclidean_cluster.launch.py

+11-2
Original file line numberDiff line numberDiff line change
@@ -76,20 +76,27 @@ def load_composable_node_param(param_path):
7676
executable="component_container",
7777
composable_node_descriptions=[],
7878
output="screen",
79+
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
80+
)
81+
82+
target_container = (
83+
LaunchConfiguration("pointcloud_container_name")
84+
if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
85+
else container
7986
)
8087

8188
use_low_height_pointcloud_loader = LoadComposableNodes(
8289
composable_node_descriptions=[
8390
low_height_cropbox_filter_component,
8491
use_low_height_euclidean_component,
8592
],
86-
target_container=container,
93+
target_container=target_container,
8794
condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")),
8895
)
8996

9097
disuse_low_height_pointcloud_loader = LoadComposableNodes(
9198
composable_node_descriptions=[disuse_low_height_euclidean_component],
92-
target_container=container,
99+
target_container=target_container,
93100
condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")),
94101
)
95102

@@ -106,6 +113,8 @@ def add_launch_arg(name: str, default_value=None):
106113
add_launch_arg("input_map", "/map/pointcloud_map"),
107114
add_launch_arg("output_clusters", "clusters"),
108115
add_launch_arg("use_low_height_cropbox", "false"),
116+
add_launch_arg("use_pointcloud_container", "false"),
117+
add_launch_arg("pointcloud_container_name", "pointcloud_container"),
109118
add_launch_arg(
110119
"euclidean_param_path",
111120
[

perception/euclidean_cluster/launch/euclidean_cluster.launch.xml

+5
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,17 @@
55
<arg name="output_clusters" default="clusters"/>
66
<arg name="use_low_height_cropbox" default="false"/>
77
<arg name="euclidean_param_path" default="$(find-pkg-share euclidean_cluster)/config/euclidean_cluster.param.yaml"/>
8+
<arg name="use_pointcloud_container" default="false"/>
9+
<arg name="pointcloud_container_name" default="pointcloud_container"/>
810

911
<include file="$(find-pkg-share euclidean_cluster)/launch/euclidean_cluster.launch.py">
1012
<arg name="input_points_raw_list" value="$(var input_pointcloud)"/>
1113
<arg name="input_map" value="$(var input_map)"/>
1214
<arg name="output_clusters" value="$(var output_clusters)"/>
1315
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
1416
<arg name="euclidean_param_path" value="$(var euclidean_param_path)"/>
17+
18+
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
19+
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
1520
</include>
1621
</launch>

perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py

+11-2
Original file line numberDiff line numberDiff line change
@@ -77,20 +77,27 @@ def load_composable_node_param(param_path):
7777
executable="component_container",
7878
composable_node_descriptions=[],
7979
output="screen",
80+
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
81+
)
82+
83+
target_container = (
84+
LaunchConfiguration("pointcloud_container_name")
85+
if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
86+
else container
8087
)
8188

8289
use_low_height_pointcloud_loader = LoadComposableNodes(
8390
composable_node_descriptions=[
8491
low_height_cropbox_filter_component,
8592
use_low_height_euclidean_component,
8693
],
87-
target_container=container,
94+
target_container=target_container,
8895
condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")),
8996
)
9097

9198
disuse_low_height_pointcloud_loader = LoadComposableNodes(
9299
composable_node_descriptions=[disuse_low_height_euclidean_component],
93-
target_container=container,
100+
target_container=target_container,
94101
condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")),
95102
)
96103
return [
@@ -110,6 +117,8 @@ def add_launch_arg(name: str, default_value=None):
110117
add_launch_arg("input_map", "/map/pointcloud_map"),
111118
add_launch_arg("output_clusters", "clusters"),
112119
add_launch_arg("use_low_height_cropbox", "false"),
120+
add_launch_arg("use_pointcloud_container", "false"),
121+
add_launch_arg("pointcloud_container_name", "pointcloud_container"),
113122
add_launch_arg(
114123
"voxel_grid_based_euclidean_param_path",
115124
[

perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml

+5
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,17 @@
55
<arg name="output_clusters" default="clusters"/>
66
<arg name="use_low_height_cropbox" default="false"/>
77
<arg name="voxel_grid_based_euclidean_param_path" default="$(find-pkg-share euclidean_cluster)/config/voxel_grid_based_euclidean_cluster.param.yaml"/>
8+
<arg name="use_pointcloud_container" default="false"/>
9+
<arg name="pointcloud_container_name" default="pointcloud_container"/>
810

911
<include file="$(find-pkg-share euclidean_cluster)/launch/voxel_grid_based_euclidean_cluster.launch.py">
1012
<arg name="input_pointcloud" value="$(var input_pointcloud)"/>
1113
<arg name="input_map" value="$(var input_map)"/>
1214
<arg name="output_clusters" value="$(var output_clusters)"/>
1315
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
1416
<arg name="voxel_grid_based_euclidean_param_path" value="$(var voxel_grid_based_euclidean_param_path)"/>
17+
18+
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
19+
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
1520
</include>
1621
</launch>

perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml

+50-1
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,9 @@
2626
<arg name="sync_param_path" default="$(find-pkg-share image_projection_based_fusion)/config/roi_sync.param.yaml"/>
2727
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
2828

29+
<arg name="use_pointcloud_container" default="false" description="use pointcloud_container"/>
30+
<arg name="pointcloud_container_name" default="pointcloud_container" description="pointcloud_container name"/>
31+
2932
<!-- for eval variable-->
3033
<arg name="input_rois_number" default="$(var input/rois_number)"/>
3134

@@ -38,7 +41,53 @@
3841
<arg name="input/image5" default="/image_raw5"/>
3942
<arg name="input/image6" default="/image_raw6"/>
4043
<arg name="input/image7" default="/image_raw7"/>
41-
<group>
44+
45+
<group if="$(var use_pointcloud_container)">
46+
<load_composable_node target="$(var pointcloud_container_name)">
47+
<composable_node pkg="image_projection_based_fusion" plugin="image_projection_based_fusion::PointPaintingFusionNode" name="pointpainting">
48+
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
49+
<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)"/>
56+
<param from="$(var sync_param_path)"/>
57+
<param from="$(var class_remapper_param_path)"/>
58+
<param name="rois_number" value="$(var input/rois_number)"/>
59+
<param name="build_only" value="$(var build_only)"/>
60+
61+
<!-- rois, camera and info -->
62+
<param name="input/rois0" value="$(var input/rois0)"/>
63+
<param name="input/camera_info0" value="$(var input/camera_info0)"/>
64+
<param name="input/image0" value="$(var input/image0)"/>
65+
<param name="input/rois1" value="$(var input/rois1)"/>
66+
<param name="input/camera_info1" value="$(var input/camera_info1)"/>
67+
<param name="input/image1" value="$(var input/image1)"/>
68+
<param name="input/rois2" value="$(var input/rois2)"/>
69+
<param name="input/camera_info2" value="$(var input/camera_info2)"/>
70+
<param name="input/image2" value="$(var input/image2)"/>
71+
<param name="input/rois3" value="$(var input/rois3)"/>
72+
<param name="input/camera_info3" value="$(var input/camera_info3)"/>
73+
<param name="input/image3" value="$(var input/image3)"/>
74+
<param name="input/rois4" value="$(var input/rois4)"/>
75+
<param name="input/camera_info4" value="$(var input/camera_info4)"/>
76+
<param name="input/image4" value="$(var input/image4)"/>
77+
<param name="input/rois5" value="$(var input/rois5)"/>
78+
<param name="input/camera_info5" value="$(var input/camera_info5)"/>
79+
<param name="input/image5" value="$(var input/image5)"/>
80+
<param name="input/rois6" value="$(var input/rois6)"/>
81+
<param name="input/camera_info6" value="$(var input/camera_info6)"/>
82+
<param name="input/image6" value="$(var input/image6)"/>
83+
<param name="input/rois7" value="$(var input/rois7)"/>
84+
<param name="input/camera_info7" value="$(var input/camera_info7)"/>
85+
<param name="input/image7" value="$(var input/image7)"/>
86+
<extra_arg name="use_intra_process_comms" value="true"/>
87+
</composable_node>
88+
</load_composable_node>
89+
</group>
90+
<group unless="$(var use_pointcloud_container)">
4291
<node pkg="image_projection_based_fusion" exec="pointpainting_fusion_node" name="pointpainting" output="screen">
4392
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
4493
<remap from="~/output/objects" to="$(var output/objects)"/>

perception/lidar_centerpoint/config/detection_class_remapper.param.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -29,9 +29,9 @@
2929
max_area_matrix:
3030
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
3131
[ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN
32-
0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR
33-
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK
34-
0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS
32+
0.000, 0.000, 36.000, 0.000, 999.999, 0.000, 0.000, 0.000, #CAR
33+
0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #TRUCK
34+
0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #BUS
3535
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER
3636
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE
3737
0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE

perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml

+41-16
Original file line numberDiff line numberDiff line change
@@ -11,20 +11,45 @@
1111
<arg name="has_twist" default="false"/>
1212
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
1313

14-
<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
15-
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
16-
<remap from="~/output/objects" to="$(var output/objects)"/>
17-
<param name="score_threshold" value="$(var score_threshold)"/>
18-
<param name="densification_world_frame_id" value="map"/>
19-
<param name="densification_num_past_frames" value="1"/>
20-
<param name="trt_precision" value="fp16"/>
21-
<param name="has_twist" value="$(var has_twist)"/>
22-
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
23-
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
24-
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
25-
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
26-
<param name="build_only" value="$(var build_only)"/>
27-
<param from="$(var model_param_path)"/>
28-
<param from="$(var class_remapper_param_path)"/>
29-
</node>
14+
<arg name="use_pointcloud_container" default="false" description="use pointcloud_container"/>
15+
<arg name="pointcloud_container_name" default="pointcloud_container" description="pointcloud_container name"/>
16+
17+
<group if="$(var use_pointcloud_container)">
18+
<load_composable_node target="$(var pointcloud_container_name)">
19+
<composable_node pkg="lidar_centerpoint" plugin="centerpoint::LidarCenterPointNode" name="lidar_centerpoint">
20+
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
21+
<remap from="~/output/objects" to="$(var output/objects)"/>
22+
<param name="score_threshold" value="$(var score_threshold)"/>
23+
<param name="densification_world_frame_id" value="map"/>
24+
<param name="densification_num_past_frames" value="1"/>
25+
<param name="trt_precision" value="fp16"/>
26+
<param name="has_twist" value="$(var has_twist)"/>
27+
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
28+
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
29+
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
30+
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
31+
<param name="build_only" value="$(var build_only)"/>
32+
<param from="$(var model_param_path)"/>
33+
<param from="$(var class_remapper_param_path)"/>
34+
</composable_node>
35+
</load_composable_node>
36+
</group>
37+
<group unless="$(var use_pointcloud_container)">
38+
<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
39+
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
40+
<remap from="~/output/objects" to="$(var output/objects)"/>
41+
<param name="score_threshold" value="$(var score_threshold)"/>
42+
<param name="densification_world_frame_id" value="map"/>
43+
<param name="densification_num_past_frames" value="1"/>
44+
<param name="trt_precision" value="fp16"/>
45+
<param name="has_twist" value="$(var has_twist)"/>
46+
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
47+
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
48+
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
49+
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
50+
<param name="build_only" value="$(var build_only)"/>
51+
<param from="$(var model_param_path)"/>
52+
<param from="$(var class_remapper_param_path)"/>
53+
</node>
54+
</group>
3055
</launch>

0 commit comments

Comments
 (0)