From 67459763bd61a57e044132174dd1c403550c1f00 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Fri, 11 Mar 2022 11:14:54 +0900 Subject: [PATCH] fix: detection launch in perception_launch (#506) Signed-off-by: Yukihiro Saito --- .../camera_lidar_fusion_based_detection.launch.xml | 8 ++++---- .../detection/lidar_based_detection.launch.xml | 1 + .../euclidean_cluster/launch/euclidean_cluster.launch.py | 2 +- .../launch/voxel_grid_based_euclidean_cluster.launch.py | 2 +- 4 files changed, 7 insertions(+), 6 deletions(-) diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml index ba7933ce68d03..16fa7234a7650 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml @@ -34,9 +34,9 @@ --> - + - + @@ -57,7 +57,7 @@ - + @@ -120,7 +120,7 @@ - + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml index 692697d6d9964..579e38e8ff46c 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml @@ -5,6 +5,7 @@ + diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index 4e34538127f13..430ef0ea49367 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -32,7 +32,7 @@ def load_composable_node_param(param_path): with open(LaunchConfiguration(param_path).perform(context), "r") as f: return yaml.safe_load(f)["/**"]["ros__parameters"] - ns = "euclidean_cluster" + ns = "" pkg = "euclidean_cluster" # set voxel grid filter as a component 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 8d36f818cf133..2cfc5142f6fd8 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 @@ -32,7 +32,7 @@ def load_composable_node_param(param_path): with open(LaunchConfiguration(param_path).perform(context), "r") as f: return yaml.safe_load(f)["/**"]["ros__parameters"] - ns = "clustering" + ns = "" pkg = "euclidean_cluster" # set compare map filter as a component