17 from ament_index_python.packages
import get_package_share_directory
18 from launch
import LaunchDescription
19 from launch.actions
import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription
20 from launch.conditions
import IfCondition, UnlessCondition
21 from launch.launch_description_sources
import PythonLaunchDescriptionSource
22 from launch.substitutions
import LaunchConfiguration
23 from launch_ros.actions
import Node, SetParameter, SetRemap
24 from launch_ros.descriptions
import ParameterFile
28 def generate_launch_description() -> LaunchDescription:
30 namespace = LaunchConfiguration(
'namespace')
31 params_file = LaunchConfiguration(
'params_file')
32 use_sim_time = LaunchConfiguration(
'use_sim_time')
33 autostart = LaunchConfiguration(
'autostart')
34 use_respawn = LaunchConfiguration(
'use_respawn')
35 log_level = LaunchConfiguration(
'log_level')
38 lifecycle_nodes = [
'map_saver']
41 bringup_dir = get_package_share_directory(
'nav2_bringup')
42 slam_toolbox_dir = get_package_share_directory(
'slam_toolbox')
43 slam_launch_file = os.path.join(slam_toolbox_dir,
'launch',
'online_sync_launch.py')
46 configured_params = ParameterFile(
48 source_file=params_file,
57 declare_namespace_cmd = DeclareLaunchArgument(
58 'namespace', default_value=
'', description=
'Top-level namespace'
61 declare_params_file_cmd = DeclareLaunchArgument(
63 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
64 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
67 declare_use_sim_time_cmd = DeclareLaunchArgument(
70 description=
'Use simulation (Gazebo) clock if true',
73 declare_autostart_cmd = DeclareLaunchArgument(
76 description=
'Automatically startup the nav2 stack',
79 declare_use_respawn_cmd = DeclareLaunchArgument(
81 default_value=
'False',
82 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
85 declare_log_level_cmd = DeclareLaunchArgument(
86 'log_level', default_value=
'info', description=
'log level'
90 start_map_server = GroupAction(
92 SetParameter(
'use_sim_time', use_sim_time),
94 package=
'nav2_map_server',
95 executable=
'map_saver_server',
99 arguments=[
'--ros-args',
'--log-level', log_level],
100 parameters=[configured_params],
103 package=
'nav2_lifecycle_manager',
104 executable=
'lifecycle_manager',
105 name=
'lifecycle_manager_slam',
107 arguments=[
'--ros-args',
'--log-level', log_level],
108 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
116 has_slam_toolbox_params = HasNodeParams(
117 source_file=params_file, node_name=
'slam_toolbox'
120 start_slam_toolbox_cmd = GroupAction(
124 SetRemap(src=
'/scan', dst=
'scan'),
125 SetRemap(src=
'/tf', dst=
'tf'),
126 SetRemap(src=
'/tf_static', dst=
'tf_static'),
127 SetRemap(src=
'/map', dst=
'map'),
129 IncludeLaunchDescription(
130 PythonLaunchDescriptionSource(slam_launch_file),
131 launch_arguments={
'use_sim_time': use_sim_time}.items(),
132 condition=UnlessCondition(has_slam_toolbox_params),
135 IncludeLaunchDescription(
136 PythonLaunchDescriptionSource(slam_launch_file),
137 launch_arguments={
'use_sim_time': use_sim_time,
138 'slam_params_file': params_file}.items(),
139 condition=IfCondition(has_slam_toolbox_params),
144 ld = LaunchDescription()
147 ld.add_action(declare_namespace_cmd)
148 ld.add_action(declare_params_file_cmd)
149 ld.add_action(declare_use_sim_time_cmd)
150 ld.add_action(declare_autostart_cmd)
151 ld.add_action(declare_use_respawn_cmd)
152 ld.add_action(declare_log_level_cmd)
155 ld.add_action(start_map_server)
158 ld.add_action(start_slam_toolbox_cmd)