17 from ament_index_python.packages
import get_package_share_directory
19 from launch
import LaunchDescription
20 from launch.actions
import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription
21 from launch.conditions
import IfCondition, UnlessCondition
22 from launch.launch_description_sources
import PythonLaunchDescriptionSource
23 from launch.substitutions
import LaunchConfiguration
24 from launch_ros.actions
import Node, SetParameter, SetRemap
25 from launch_ros.descriptions
import ParameterFile
29 def generate_launch_description():
31 namespace = LaunchConfiguration(
'namespace')
32 params_file = LaunchConfiguration(
'params_file')
33 use_sim_time = LaunchConfiguration(
'use_sim_time')
34 autostart = LaunchConfiguration(
'autostart')
35 use_respawn = LaunchConfiguration(
'use_respawn')
36 log_level = LaunchConfiguration(
'log_level')
39 lifecycle_nodes = [
'map_saver']
42 bringup_dir = get_package_share_directory(
'nav2_bringup')
43 slam_toolbox_dir = get_package_share_directory(
'slam_toolbox')
44 slam_launch_file = os.path.join(slam_toolbox_dir,
'launch',
'online_sync_launch.py')
47 configured_params = ParameterFile(
49 source_file=params_file,
58 declare_namespace_cmd = DeclareLaunchArgument(
59 'namespace', default_value=
'', description=
'Top-level namespace'
62 declare_params_file_cmd = DeclareLaunchArgument(
64 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
65 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
68 declare_use_sim_time_cmd = DeclareLaunchArgument(
71 description=
'Use simulation (Gazebo) clock if true',
74 declare_autostart_cmd = DeclareLaunchArgument(
77 description=
'Automatically startup the nav2 stack',
80 declare_use_respawn_cmd = DeclareLaunchArgument(
82 default_value=
'False',
83 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
86 declare_log_level_cmd = DeclareLaunchArgument(
87 'log_level', default_value=
'info', description=
'log level'
91 start_map_server = GroupAction(
93 SetParameter(
'use_sim_time', use_sim_time),
95 package=
'nav2_map_server',
96 executable=
'map_saver_server',
100 arguments=[
'--ros-args',
'--log-level', log_level],
101 parameters=[configured_params],
104 package=
'nav2_lifecycle_manager',
105 executable=
'lifecycle_manager',
106 name=
'lifecycle_manager_slam',
108 arguments=[
'--ros-args',
'--log-level', log_level],
109 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
117 has_slam_toolbox_params = HasNodeParams(
118 source_file=params_file, node_name=
'slam_toolbox'
121 start_slam_toolbox_cmd = GroupAction(
125 SetRemap(src=
'/scan', dst=
'scan'),
126 SetRemap(src=
'/tf', dst=
'tf'),
127 SetRemap(src=
'/tf_static', dst=
'tf_static'),
128 SetRemap(src=
'/map', dst=
'map'),
130 IncludeLaunchDescription(
131 PythonLaunchDescriptionSource(slam_launch_file),
132 launch_arguments={
'use_sim_time': use_sim_time}.items(),
133 condition=UnlessCondition(has_slam_toolbox_params),
136 IncludeLaunchDescription(
137 PythonLaunchDescriptionSource(slam_launch_file),
138 launch_arguments={
'use_sim_time': use_sim_time,
139 'slam_params_file': params_file}.items(),
140 condition=IfCondition(has_slam_toolbox_params),
145 ld = LaunchDescription()
148 ld.add_action(declare_namespace_cmd)
149 ld.add_action(declare_params_file_cmd)
150 ld.add_action(declare_use_sim_time_cmd)
151 ld.add_action(declare_autostart_cmd)
152 ld.add_action(declare_use_respawn_cmd)
153 ld.add_action(declare_log_level_cmd)
156 ld.add_action(start_map_server)
159 ld.add_action(start_slam_toolbox_cmd)