Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
slam_launch.py
1 # Copyright (c) 2020 Samsung Research Russia
2 #
3 # Licensed under the Apache License, Version 2.0 (the "License");
4 # you may not use this file except in compliance with the License.
5 # You may obtain a copy of the License at
6 #
7 # http://www.apache.org/licenses/LICENSE-2.0
8 #
9 # Unless required by applicable law or agreed to in writing, software
10 # distributed under the License is distributed on an "AS IS" BASIS,
11 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 # See the License for the specific language governing permissions and
13 # limitations under the License.
14 
15 import os
16 
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, PushROSNamespace, SetParameter, SetRemap
24 from launch_ros.descriptions import ParameterFile
25 from nav2_common.launch import HasNodeParams, LaunchConfigAsBool, RewrittenYaml
26 
27 
28 def generate_launch_description() -> LaunchDescription:
29  # Input parameters declaration
30  namespace = LaunchConfiguration('namespace')
31  params_file = LaunchConfiguration('params_file')
32  use_sim_time = LaunchConfigAsBool('use_sim_time')
33  autostart = LaunchConfigAsBool('autostart')
34  use_respawn = LaunchConfigAsBool('use_respawn')
35  log_level = LaunchConfiguration('log_level')
36 
37  # Variables
38  lifecycle_nodes = ['map_saver']
39 
40  # Getting directories and launch-files
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')
44 
45  # Create our own temporary YAML files that include substitutions
46  configured_params = ParameterFile(
47  RewrittenYaml(
48  source_file=params_file,
49  root_key=namespace,
50  param_rewrites={},
51  convert_types=True,
52  ),
53  allow_substs=True,
54  )
55 
56  # Declare the launch arguments
57  declare_namespace_cmd = DeclareLaunchArgument(
58  'namespace', default_value='', description='Top-level namespace'
59  )
60 
61  declare_params_file_cmd = DeclareLaunchArgument(
62  'params_file',
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',
65  )
66 
67  declare_use_sim_time_cmd = DeclareLaunchArgument(
68  'use_sim_time',
69  default_value='True',
70  description='Use simulation (Gazebo) clock if true',
71  )
72 
73  declare_autostart_cmd = DeclareLaunchArgument(
74  'autostart',
75  default_value='True',
76  description='Automatically startup the nav2 stack',
77  )
78 
79  declare_use_respawn_cmd = DeclareLaunchArgument(
80  'use_respawn',
81  default_value='False',
82  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
83  )
84 
85  declare_log_level_cmd = DeclareLaunchArgument(
86  'log_level', default_value='info', description='log level'
87  )
88 
89  # Nodes launching commands
90  start_map_server = GroupAction(
91  actions=[
92  PushROSNamespace(namespace),
93  SetParameter('use_sim_time', use_sim_time),
94  Node(
95  package='nav2_map_server',
96  executable='map_saver_server',
97  output='screen',
98  respawn=use_respawn,
99  respawn_delay=2.0,
100  arguments=['--ros-args', '--log-level', log_level],
101  parameters=[configured_params],
102  ),
103  Node(
104  package='nav2_lifecycle_manager',
105  executable='lifecycle_manager',
106  name='lifecycle_manager_slam',
107  output='screen',
108  arguments=['--ros-args', '--log-level', log_level],
109  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
110  ),
111  ]
112  )
113 
114  # If the provided param file doesn't have slam_toolbox params, we must remove the 'params_file'
115  # LaunchConfiguration, or it will be passed automatically to slam_toolbox and will not load
116  # the default file
117  has_slam_toolbox_params = HasNodeParams(
118  source_file=params_file, node_name='slam_toolbox'
119  )
120 
121  start_slam_toolbox_cmd = GroupAction(
122 
123  actions=[
124  PushROSNamespace(namespace),
125 
126  # Remapping required to have a slam session subscribe & publish in optional namespaces
127  SetRemap(src='/scan', dst='scan'),
128  SetRemap(src='/tf', dst='tf'),
129  SetRemap(src='/tf_static', dst='tf_static'),
130  SetRemap(src='/map', dst='map'),
131 
132  IncludeLaunchDescription(
133  PythonLaunchDescriptionSource(slam_launch_file),
134  launch_arguments={'use_sim_time': use_sim_time}.items(),
135  condition=UnlessCondition(has_slam_toolbox_params),
136  ),
137 
138  IncludeLaunchDescription(
139  PythonLaunchDescriptionSource(slam_launch_file),
140  launch_arguments={'use_sim_time': use_sim_time,
141  'slam_params_file': params_file}.items(),
142  condition=IfCondition(has_slam_toolbox_params),
143  )
144  ]
145  )
146 
147  ld = LaunchDescription()
148 
149  # Declare the launch options
150  ld.add_action(declare_namespace_cmd)
151  ld.add_action(declare_params_file_cmd)
152  ld.add_action(declare_use_sim_time_cmd)
153  ld.add_action(declare_autostart_cmd)
154  ld.add_action(declare_use_respawn_cmd)
155  ld.add_action(declare_log_level_cmd)
156 
157  # Running Map Saver Server
158  ld.add_action(start_map_server)
159 
160  # Running SLAM Toolbox (Only one of them will be run)
161  ld.add_action(start_slam_toolbox_cmd)
162 
163  return ld