Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
localization_launch.py
1 # Copyright (c) 2018 Intel Corporation
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, SetEnvironmentVariable
20 from launch.conditions import IfCondition
21 from launch.substitutions import (EqualsSubstitution, LaunchConfiguration, NotEqualsSubstitution,
22  PythonExpression)
23 from launch_ros.actions import LoadComposableNodes, Node, SetParameter
24 from launch_ros.descriptions import ComposableNode, ParameterFile
25 from nav2_common.launch import RewrittenYaml
26 
27 
28 def generate_launch_description() -> LaunchDescription:
29  # Get the launch directory
30  bringup_dir = get_package_share_directory('nav2_bringup')
31 
32  namespace = LaunchConfiguration('namespace')
33  map_yaml_file = LaunchConfiguration('map')
34  use_sim_time = LaunchConfiguration('use_sim_time')
35  autostart = LaunchConfiguration('autostart')
36  params_file = LaunchConfiguration('params_file')
37  use_composition = LaunchConfiguration('use_composition')
38  container_name = LaunchConfiguration('container_name')
39  container_name_full = (namespace, '/', container_name)
40  use_respawn = LaunchConfiguration('use_respawn')
41  log_level = LaunchConfiguration('log_level')
42 
43  lifecycle_nodes = ['map_server', 'amcl']
44 
45  # Map fully qualified names to relative ones so the node's namespace can be prepended.
46  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
47 
48  configured_params = ParameterFile(
49  RewrittenYaml(
50  source_file=params_file,
51  root_key=namespace,
52  param_rewrites={},
53  convert_types=True,
54  ),
55  allow_substs=True,
56  )
57 
58  stdout_linebuf_envvar = SetEnvironmentVariable(
59  'RCUTILS_LOGGING_BUFFERED_STREAM', '1'
60  )
61 
62  declare_namespace_cmd = DeclareLaunchArgument(
63  'namespace', default_value='', description='Top-level namespace'
64  )
65 
66  declare_map_yaml_cmd = DeclareLaunchArgument(
67  'map', default_value='', description='Full path to map yaml file to load'
68  )
69 
70  declare_use_sim_time_cmd = DeclareLaunchArgument(
71  'use_sim_time',
72  default_value='false',
73  description='Use simulation (Gazebo) clock if true',
74  )
75 
76  declare_params_file_cmd = DeclareLaunchArgument(
77  'params_file',
78  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
79  description='Full path to the ROS2 parameters file to use for all launched nodes',
80  )
81 
82  declare_autostart_cmd = DeclareLaunchArgument(
83  'autostart',
84  default_value='true',
85  description='Automatically startup the nav2 stack',
86  )
87 
88  declare_use_composition_cmd = DeclareLaunchArgument(
89  'use_composition',
90  default_value='False',
91  description='Use composed bringup if True',
92  )
93 
94  declare_container_name_cmd = DeclareLaunchArgument(
95  'container_name',
96  default_value='nav2_container',
97  description='the name of container that nodes will load in if use composition',
98  )
99 
100  declare_use_respawn_cmd = DeclareLaunchArgument(
101  'use_respawn',
102  default_value='False',
103  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
104  )
105 
106  declare_log_level_cmd = DeclareLaunchArgument(
107  'log_level', default_value='info', description='log level'
108  )
109 
110  load_nodes = GroupAction(
111  condition=IfCondition(PythonExpression(['not ', use_composition])),
112  actions=[
113  SetParameter('use_sim_time', use_sim_time),
114  Node(
115  condition=IfCondition(
116  EqualsSubstitution(LaunchConfiguration('map'), '')
117  ),
118  package='nav2_map_server',
119  executable='map_server',
120  name='map_server',
121  output='screen',
122  respawn=use_respawn,
123  respawn_delay=2.0,
124  parameters=[configured_params],
125  arguments=['--ros-args', '--log-level', log_level],
126  remappings=remappings,
127  ),
128  Node(
129  condition=IfCondition(
130  NotEqualsSubstitution(LaunchConfiguration('map'), '')
131  ),
132  package='nav2_map_server',
133  executable='map_server',
134  name='map_server',
135  output='screen',
136  respawn=use_respawn,
137  respawn_delay=2.0,
138  parameters=[configured_params, {'yaml_filename': map_yaml_file}],
139  arguments=['--ros-args', '--log-level', log_level],
140  remappings=remappings,
141  ),
142  Node(
143  package='nav2_amcl',
144  executable='amcl',
145  name='amcl',
146  output='screen',
147  respawn=use_respawn,
148  respawn_delay=2.0,
149  parameters=[configured_params],
150  arguments=['--ros-args', '--log-level', log_level],
151  remappings=remappings,
152  ),
153  Node(
154  package='nav2_lifecycle_manager',
155  executable='lifecycle_manager',
156  name='lifecycle_manager_localization',
157  output='screen',
158  arguments=['--ros-args', '--log-level', log_level],
159  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
160  ),
161  ],
162  )
163  # LoadComposableNode for map server twice depending if we should use the
164  # value of map from a CLI or launch default or user defined value in the
165  # yaml configuration file. They are separated since the conditions
166  # currently only work on the LoadComposableNodes commands and not on the
167  # ComposableNode node function itself
168  load_composable_nodes = GroupAction(
169  condition=IfCondition(use_composition),
170  actions=[
171  SetParameter('use_sim_time', use_sim_time),
172  LoadComposableNodes(
173  target_container=container_name_full,
174  condition=IfCondition(
175  EqualsSubstitution(LaunchConfiguration('map'), '')
176  ),
177  composable_node_descriptions=[
178  ComposableNode(
179  package='nav2_map_server',
180  plugin='nav2_map_server::MapServer',
181  name='map_server',
182  parameters=[configured_params],
183  remappings=remappings,
184  ),
185  ],
186  ),
187  LoadComposableNodes(
188  target_container=container_name_full,
189  condition=IfCondition(
190  NotEqualsSubstitution(LaunchConfiguration('map'), '')
191  ),
192  composable_node_descriptions=[
193  ComposableNode(
194  package='nav2_map_server',
195  plugin='nav2_map_server::MapServer',
196  name='map_server',
197  parameters=[
198  configured_params,
199  {'yaml_filename': map_yaml_file},
200  ],
201  remappings=remappings,
202  ),
203  ],
204  ),
205  LoadComposableNodes(
206  target_container=container_name_full,
207  composable_node_descriptions=[
208  ComposableNode(
209  package='nav2_amcl',
210  plugin='nav2_amcl::AmclNode',
211  name='amcl',
212  parameters=[configured_params],
213  remappings=remappings,
214  ),
215  ComposableNode(
216  package='nav2_lifecycle_manager',
217  plugin='nav2_lifecycle_manager::LifecycleManager',
218  name='lifecycle_manager_localization',
219  parameters=[
220  {'autostart': autostart, 'node_names': lifecycle_nodes}
221  ],
222  ),
223  ],
224  ),
225  ],
226  )
227 
228  # Create the launch description and populate
229  ld = LaunchDescription()
230 
231  # Set environment variables
232  ld.add_action(stdout_linebuf_envvar)
233 
234  # Declare the launch options
235  ld.add_action(declare_namespace_cmd)
236  ld.add_action(declare_map_yaml_cmd)
237  ld.add_action(declare_use_sim_time_cmd)
238  ld.add_action(declare_params_file_cmd)
239  ld.add_action(declare_autostart_cmd)
240  ld.add_action(declare_use_composition_cmd)
241  ld.add_action(declare_container_name_cmd)
242  ld.add_action(declare_use_respawn_cmd)
243  ld.add_action(declare_log_level_cmd)
244 
245  # Add the actions to launch all of the localiztion nodes
246  ld.add_action(load_nodes)
247  ld.add_action(load_composable_nodes)
248 
249  return ld