From fdf60d67236daa0d2c137d7d3cacc25ec924f068 Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 30 Jan 2024 14:48:00 +0900 Subject: [PATCH 01/13] feat(lidar_centerpoint,image_projection_based_fusion): add pointcloud_container option Signed-off-by: kminoda --- .../detector/camera_lidar_detector.launch.xml | 3 + .../detector/lidar_dnn_detector.launch.xml | 3 + .../launch/perception.launch.xml | 2 +- .../launch/pointpainting_fusion.launch.xml | 51 ++++++++++++++++- .../detection_class_remapper.param.yaml | 6 +- .../launch/lidar_centerpoint.launch.xml | 57 +++++++++++++------ 6 files changed, 101 insertions(+), 21 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml index 1c9201a9af8b3..2232feb6d7c67 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml @@ -85,6 +85,9 @@ + + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml index 1a97659b357d8..5b5fabd4dd886 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml @@ -22,6 +22,9 @@ + + + diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index e8c19382864ba..f1d0512d0d69e 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -43,7 +43,7 @@ - + diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 33781461fa1cc..952a43afcbb12 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -26,6 +26,9 @@ + + + @@ -38,7 +41,53 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml index ed378ffa44a70..084748dd97c64 100644 --- a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml +++ b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml @@ -29,9 +29,9 @@ max_area_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN - 0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR - 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK - 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 36.000, 0.000, 100.000, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 100.000, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 100.000, 0.000, 0.000, 0.000, #BUS 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index a7f181ab78ac6..b1c1797ffc21e 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -11,20 +11,45 @@ - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 50211e55b6c0878d494462ff04d5069a528c4ab4 Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 30 Jan 2024 14:48:37 +0900 Subject: [PATCH 02/13] revert lidar_perception_model Signed-off-by: kminoda --- launch/tier4_perception_launch/launch/perception.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index f1d0512d0d69e..e8c19382864ba 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -43,7 +43,7 @@ - + From 66110e0521070a4f99ffd4daf603dbbc4f854278 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 30 Jan 2024 05:53:17 +0000 Subject: [PATCH 03/13] style(pre-commit): autofix --- .../launch/pointpainting_fusion.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 952a43afcbb12..c93e91e48d1c1 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -85,7 +85,7 @@ - + From ca72a0c40b27a163e6839b08d5c7befb973891be Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 30 Jan 2024 14:59:56 +0900 Subject: [PATCH 04/13] fix: add options Signed-off-by: kminoda --- .../detector/lidar_rule_detector.launch.xml | 3 +++ .../launch/euclidean_cluster.launch.py | 12 ++++++++++-- .../launch/euclidean_cluster.launch.xml | 5 +++++ .../voxel_grid_based_euclidean_cluster.launch.py | 12 ++++++++++-- .../voxel_grid_based_euclidean_cluster.launch.xml | 5 +++++ 5 files changed, 33 insertions(+), 4 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml index ce34640bd3179..cec0c3bc05aac 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml @@ -26,6 +26,9 @@ + + + diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index 66c25396a656e..ac97c9ea33ec6 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -78,18 +78,24 @@ def load_composable_node_param(param_path): output="screen", ) + target_container = ( + LaunchConfiguration("pointcloud_container_name") + if LaunchConfiguration("use_pointcloud_container") + else container + ) + use_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[ low_height_cropbox_filter_component, use_low_height_euclidean_component, ], - target_container=container, + target_container=target_container, condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")), ) disuse_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[disuse_low_height_euclidean_component], - target_container=container, + target_container=target_container, condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")), ) @@ -106,6 +112,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_map", "/map/pointcloud_map"), add_launch_arg("output_clusters", "clusters"), add_launch_arg("use_low_height_cropbox", "false"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), add_launch_arg( "euclidean_param_path", [ diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml b/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml index fd1ea82befae0..f4deeccf7b76c 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml @@ -5,6 +5,8 @@ + + @@ -12,5 +14,8 @@ + + + diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index 00bcd4422bd3c..f4c5829ec6c8d 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -79,18 +79,24 @@ def load_composable_node_param(param_path): output="screen", ) + target_container = ( + LaunchConfiguration("pointcloud_container_name") + if LaunchConfiguration("use_pointcloud_container") + else container + ) + use_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[ low_height_cropbox_filter_component, use_low_height_euclidean_component, ], - target_container=container, + target_container=target_container, condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")), ) disuse_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[disuse_low_height_euclidean_component], - target_container=container, + target_container=target_container, condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")), ) return [ @@ -110,6 +116,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_map", "/map/pointcloud_map"), add_launch_arg("output_clusters", "clusters"), add_launch_arg("use_low_height_cropbox", "false"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), add_launch_arg( "voxel_grid_based_euclidean_param_path", [ diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml index b6a426dabfd12..3a7c685d8f449 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml @@ -5,6 +5,8 @@ + + @@ -12,5 +14,8 @@ + + + From 30bac0d336973f34b6ef1314a857f66217f38243 Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 30 Jan 2024 15:07:11 +0900 Subject: [PATCH 05/13] fix: fix default param Signed-off-by: kminoda --- .../config/detection_class_remapper.param.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml index 084748dd97c64..baea087c96bca 100644 --- a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml +++ b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml @@ -29,9 +29,9 @@ max_area_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN - 0.000, 0.000, 36.000, 0.000, 100.000, 0.000, 0.000, 0.000, #CAR - 0.000, 0.000, 0.000, 0.000, 100.000, 0.000, 0.000, 0.000, #TRUCK - 0.000, 0.000, 0.000, 0.000, 100.000, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 36.000, 0.000, 999.999, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #BUS 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE From eb38c1e04a2ed06a32e53376e9131aec5fe152ed Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 30 Jan 2024 15:10:26 +0900 Subject: [PATCH 06/13] update node name Signed-off-by: kminoda --- .../lidar_centerpoint/launch/lidar_centerpoint.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index b1c1797ffc21e..9e9dcde425ccb 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -16,7 +16,7 @@ - + From a80f4dea9b2c3006555d72b11b981322b902692b Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 30 Jan 2024 15:23:24 +0900 Subject: [PATCH 07/13] fix: fix IfCondition Signed-off-by: kminoda --- perception/euclidean_cluster/launch/euclidean_cluster.launch.py | 2 +- .../launch/voxel_grid_based_euclidean_cluster.launch.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index ac97c9ea33ec6..7a1ab002336ef 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -80,7 +80,7 @@ def load_composable_node_param(param_path): target_container = ( LaunchConfiguration("pointcloud_container_name") - if LaunchConfiguration("use_pointcloud_container") + if IfCondition(LaunchConfiguration("use_pointcloud_container")) else container ) diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index f4c5829ec6c8d..b82b85362053e 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -81,7 +81,7 @@ def load_composable_node_param(param_path): target_container = ( LaunchConfiguration("pointcloud_container_name") - if LaunchConfiguration("use_pointcloud_container") + if IfCondition(LaunchConfiguration("use_pointcloud_container")) else container ) From 2fba982b599676cf0aa7f545343af862115998f6 Mon Sep 17 00:00:00 2001 From: kminoda Date: Tue, 30 Jan 2024 16:11:08 +0900 Subject: [PATCH 08/13] fix pointpainting namespace Signed-off-by: kminoda --- .../launch/pointpainting_fusion.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index c93e91e48d1c1..db13d73e37fa7 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -44,7 +44,7 @@ - + From 704589bc29a3c04fd69e2022788567ff10c99376 Mon Sep 17 00:00:00 2001 From: kminoda Date: Wed, 31 Jan 2024 09:23:06 +0900 Subject: [PATCH 09/13] fix: fix launch args Signed-off-by: kminoda --- .../lidar_centerpoint/launch/lidar_centerpoint.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index 9e9dcde425ccb..a7f9fddd858d5 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -18,7 +18,7 @@ - + From a8b0d46a52fc8059ffc73c1eb8fca0545d56c3de Mon Sep 17 00:00:00 2001 From: kminoda Date: Wed, 31 Jan 2024 09:44:42 +0900 Subject: [PATCH 10/13] fix(euclidean_cluster): do not launch individual container when use_pointcloud_container is true Signed-off-by: kminoda --- perception/euclidean_cluster/launch/euclidean_cluster.launch.py | 1 + .../launch/voxel_grid_based_euclidean_cluster.launch.py | 1 + 2 files changed, 2 insertions(+) diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index 7a1ab002336ef..cfbbeb5ea0762 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -76,6 +76,7 @@ def load_composable_node_param(param_path): executable="component_container", composable_node_descriptions=[], output="screen", + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), ) target_container = ( diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index b82b85362053e..7df3f701a1433 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -77,6 +77,7 @@ def load_composable_node_param(param_path): executable="component_container", composable_node_descriptions=[], output="screen", + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), ) target_container = ( From 24f6e507f117ee07ee6a4088900f132147748411 Mon Sep 17 00:00:00 2001 From: kminoda Date: Wed, 31 Jan 2024 10:37:43 +0900 Subject: [PATCH 11/13] fix(euclidean_cluster): fix launch condition Signed-off-by: kminoda --- .../launch/voxel_grid_based_euclidean_cluster.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index 7df3f701a1433..607e1bf30ccaa 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -82,7 +82,7 @@ def load_composable_node_param(param_path): target_container = ( LaunchConfiguration("pointcloud_container_name") - if IfCondition(LaunchConfiguration("use_pointcloud_container")) + if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) else container ) From 095e70f1b476e5930f4b5fdf6fbaad2876f07eee Mon Sep 17 00:00:00 2001 From: kminoda Date: Wed, 31 Jan 2024 10:37:53 +0900 Subject: [PATCH 12/13] fix(euclidean_cluster): fix launch condition Signed-off-by: kminoda --- perception/euclidean_cluster/launch/euclidean_cluster.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index cfbbeb5ea0762..b8d4f61a9cf28 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -81,7 +81,7 @@ def load_composable_node_param(param_path): target_container = ( LaunchConfiguration("pointcloud_container_name") - if IfCondition(LaunchConfiguration("use_pointcloud_container")) + if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) else container ) From 9238f2ccd23100cb9c702eadc1097994e37600d4 Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 31 Jan 2024 23:08:24 +0900 Subject: [PATCH 13/13] Update perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- .../lidar_centerpoint/launch/lidar_centerpoint.launch.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index a7f9fddd858d5..1210875770510 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -37,7 +37,7 @@ - +