From d27e60b73dc36a0042cc754020b20d3a761ff337 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Tue, 2 Mar 2021 09:28:33 +0900 Subject: [PATCH] Fix aip_xx1's pointcloud_preprocessor.launch.py (#72) Signed-off-by: Kenji Miyake --- .../launch/aip_xx1/pointcloud_preprocessor.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/launch/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py b/launch/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py index a13afd6504f46..3d84321720bda 100644 --- a/launch/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py +++ b/launch/sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py @@ -61,7 +61,7 @@ def launch_setup(context, *args, **kwargs): 'input_topics': ['/sensing/lidar/top/outlier_filtered/pointcloud', '/sensing/lidar/left/outlier_filtered/pointcloud', '/sensing/lidar/right/outlier_filtered/pointcloud'], - 'output_frame': 'base_link', + 'output_frame': LaunchConfiguration('base_frame'), 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'), }] ) @@ -75,7 +75,7 @@ def launch_setup(context, *args, **kwargs): ('output', 'concatenated/pointcloud'), ], parameters=[{ - 'output_frame': 'base_link', + 'output_frame': LaunchConfiguration('base_frame'), 'min_z': vehicle_info['min_height_offset'], 'max_z': vehicle_info['max_height_offset'], 'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),