Nav2 Navigation Stack - humble  humble
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 
19 from launch import LaunchDescription
20 from launch.actions import DeclareLaunchArgument, 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
25 from launch_ros.descriptions import ParameterFile
26 from nav2_common.launch import HasNodeParams, RewrittenYaml
27 
28 
29 def generate_launch_description():
30  # Input parameters declaration
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')
37 
38  # Variables
39  lifecycle_nodes = ['map_saver']
40 
41  # Getting directories and launch-files
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')
45 
46  # Create our own temporary YAML files that include substitutions
47  param_substitutions = {
48  'use_sim_time': use_sim_time}
49 
50  configured_params = ParameterFile(
51  RewrittenYaml(
52  source_file=params_file,
53  root_key=namespace,
54  param_rewrites=param_substitutions,
55  convert_types=True),
56  allow_substs=True)
57 
58  # Declare the launch arguments
59  declare_namespace_cmd = DeclareLaunchArgument(
60  'namespace',
61  default_value='',
62  description='Top-level namespace')
63 
64  declare_params_file_cmd = DeclareLaunchArgument(
65  'params_file',
66  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
67  description='Full path to the ROS2 parameters file to use for all launched nodes')
68 
69  declare_use_sim_time_cmd = DeclareLaunchArgument(
70  'use_sim_time',
71  default_value='True',
72  description='Use simulation (Gazebo) clock if true')
73 
74  declare_autostart_cmd = DeclareLaunchArgument(
75  'autostart', default_value='True',
76  description='Automatically startup the nav2 stack')
77 
78  declare_use_respawn_cmd = DeclareLaunchArgument(
79  'use_respawn', default_value='False',
80  description='Whether to respawn if a node crashes. Applied when composition is disabled.')
81 
82  declare_log_level_cmd = DeclareLaunchArgument(
83  'log_level', default_value='info',
84  description='log level')
85 
86  # Nodes launching commands
87 
88  start_map_saver_server_cmd = Node(
89  package='nav2_map_server',
90  executable='map_saver_server',
91  output='screen',
92  respawn=use_respawn,
93  respawn_delay=2.0,
94  arguments=['--ros-args', '--log-level', log_level],
95  parameters=[configured_params])
96 
97  start_lifecycle_manager_cmd = Node(
98  package='nav2_lifecycle_manager',
99  executable='lifecycle_manager',
100  name='lifecycle_manager_slam',
101  output='screen',
102  arguments=['--ros-args', '--log-level', log_level],
103  parameters=[{'use_sim_time': use_sim_time},
104  {'autostart': autostart},
105  {'node_names': lifecycle_nodes}])
106 
107  # If the provided param file doesn't have slam_toolbox params, we must remove the 'params_file'
108  # LaunchConfiguration, or it will be passed automatically to slam_toolbox and will not load
109  # the default file
110  has_slam_toolbox_params = HasNodeParams(source_file=params_file,
111  node_name='slam_toolbox')
112 
113  start_slam_toolbox_cmd = IncludeLaunchDescription(
114  PythonLaunchDescriptionSource(slam_launch_file),
115  launch_arguments={'use_sim_time': use_sim_time}.items(),
116  condition=UnlessCondition(has_slam_toolbox_params))
117 
118  start_slam_toolbox_cmd_with_params = IncludeLaunchDescription(
119  PythonLaunchDescriptionSource(slam_launch_file),
120  launch_arguments={'use_sim_time': use_sim_time,
121  'slam_params_file': params_file}.items(),
122  condition=IfCondition(has_slam_toolbox_params))
123 
124  ld = LaunchDescription()
125 
126  # Declare the launch options
127  ld.add_action(declare_namespace_cmd)
128  ld.add_action(declare_params_file_cmd)
129  ld.add_action(declare_use_sim_time_cmd)
130  ld.add_action(declare_autostart_cmd)
131  ld.add_action(declare_use_respawn_cmd)
132  ld.add_action(declare_log_level_cmd)
133 
134  # Running Map Saver Server
135  ld.add_action(start_map_saver_server_cmd)
136  ld.add_action(start_lifecycle_manager_cmd)
137 
138  # Running SLAM Toolbox (Only one of them will be run)
139  ld.add_action(start_slam_toolbox_cmd)
140  ld.add_action(start_slam_toolbox_cmd_with_params)
141 
142  return ld