diff --git a/launch/online_async_launch.py b/launch/online_async_launch.py index 0bebe4a99..2fd82c819 100644 --- a/launch/online_async_launch.py +++ b/launch/online_async_launch.py @@ -1,3 +1,5 @@ +import os + from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration @@ -7,15 +9,21 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time') + params_file = LaunchConfiguration('params_file') declare_use_sim_time_argument = DeclareLaunchArgument( 'use_sim_time', default_value='true', description='Use simulation/Gazebo clock') + declare_params_file_cmd = DeclareLaunchArgument( + 'params_file', + default_value=os.path.join(get_package_share_directory("slam_toolbox"), + 'config', 'mapper_params_online_async.yaml'), + description='Full path to the ROS2 parameters file to use for the slam_toolbox node') start_async_slam_toolbox_node = Node( parameters=[ - get_package_share_directory("slam_toolbox") + '/config/mapper_params_online_async.yaml', + params_file, {'use_sim_time': use_sim_time} ], package='slam_toolbox', @@ -26,6 +34,7 @@ def generate_launch_description(): ld = LaunchDescription() ld.add_action(declare_use_sim_time_argument) + ld.add_action(declare_params_file_cmd) ld.add_action(start_async_slam_toolbox_node) return ld diff --git a/launch/online_sync_launch.py b/launch/online_sync_launch.py index ae38653da..ca1694e7d 100644 --- a/launch/online_sync_launch.py +++ b/launch/online_sync_launch.py @@ -1,3 +1,5 @@ +import os + from launch import LaunchDescription from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration @@ -7,15 +9,21 @@ def generate_launch_description(): use_sim_time = LaunchConfiguration('use_sim_time') + params_file = LaunchConfiguration('params_file') declare_use_sim_time_argument = DeclareLaunchArgument( 'use_sim_time', default_value='true', description='Use simulation/Gazebo clock') + declare_params_file_cmd = DeclareLaunchArgument( + 'params_file', + default_value=os.path.join(get_package_share_directory("slam_toolbox"), + 'config', 'mapper_params_online_sync.yaml'), + description='Full path to the ROS2 parameters file to use for the slam_toolbox node') start_sync_slam_toolbox_node = Node( parameters=[ - get_package_share_directory("slam_toolbox") + '/config/mapper_params_online_sync.yaml', + params_file, {'use_sim_time': use_sim_time} ], package='slam_toolbox', @@ -26,6 +34,7 @@ def generate_launch_description(): ld = LaunchDescription() ld.add_action(declare_use_sim_time_argument) + ld.add_action(declare_params_file_cmd) ld.add_action(start_sync_slam_toolbox_node) return ld