From c03bd4bdb70117efffc328e5fe6e57426f169b3b Mon Sep 17 00:00:00 2001 From: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com> Date: Mon, 4 Mar 2024 18:12:12 +0900 Subject: [PATCH] feat(tier4_localization_component_launch): change the default input pointcloud of localization into the concatenated pointcloud (#899) * Make concat pointcloud default Signed-off-by: TaikiYamada4 * style(pre-commit): autofix --------- Signed-off-by: TaikiYamada4 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../components/tier4_localization_component.launch.xml | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/autoware_launch/launch/components/tier4_localization_component.launch.xml b/autoware_launch/launch/components/tier4_localization_component.launch.xml index 3ccd98104d..b8387c1d25 100644 --- a/autoware_launch/launch/components/tier4_localization_component.launch.xml +++ b/autoware_launch/launch/components/tier4_localization_component.launch.xml @@ -3,12 +3,8 @@ - - + + @@ -16,7 +12,7 @@ - +