Nav2 Navigation Stack - humble  humble
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 
19 from launch import LaunchDescription
20 from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
21 from launch.conditions import IfCondition
22 from launch.substitutions import LaunchConfiguration, PythonExpression
23 from launch_ros.actions import LoadComposableNodes
24 from launch_ros.actions import Node
25 from launch_ros.descriptions import ComposableNode, ParameterFile
26 from nav2_common.launch import RewrittenYaml
27 
28 
29 def generate_launch_description():
30  # Get the launch directory
31  bringup_dir = get_package_share_directory('nav2_bringup')
32 
33  namespace = LaunchConfiguration('namespace')
34  map_yaml_file = LaunchConfiguration('map')
35  use_sim_time = LaunchConfiguration('use_sim_time')
36  autostart = LaunchConfiguration('autostart')
37  params_file = LaunchConfiguration('params_file')
38  use_composition = LaunchConfiguration('use_composition')
39  container_name = LaunchConfiguration('container_name')
40  container_name_full = (namespace, '/', container_name)
41  use_respawn = LaunchConfiguration('use_respawn')
42  log_level = LaunchConfiguration('log_level')
43 
44  lifecycle_nodes = ['map_server', 'amcl']
45 
46  # Map fully qualified names to relative ones so the node's namespace can be prepended.
47  # In case of the transforms (tf), currently, there doesn't seem to be a better alternative
48  # https://github.com/ros/geometry2/issues/32
49  # https://github.com/ros/robot_state_publisher/pull/30
50  # TODO(orduno) Substitute with `PushNodeRemapping`
51  # https://github.com/ros2/launch_ros/issues/56
52  remappings = [('/tf', 'tf'),
53  ('/tf_static', 'tf_static')]
54 
55  # Create our own temporary YAML files that include substitutions
56  param_substitutions = {
57  'use_sim_time': use_sim_time,
58  'yaml_filename': map_yaml_file}
59 
60  configured_params = ParameterFile(
61  RewrittenYaml(
62  source_file=params_file,
63  root_key=namespace,
64  param_rewrites=param_substitutions,
65  convert_types=True),
66  allow_substs=True)
67 
68  stdout_linebuf_envvar = SetEnvironmentVariable(
69  'RCUTILS_LOGGING_BUFFERED_STREAM', '1')
70 
71  declare_namespace_cmd = DeclareLaunchArgument(
72  'namespace',
73  default_value='',
74  description='Top-level namespace')
75 
76  declare_map_yaml_cmd = DeclareLaunchArgument(
77  'map',
78  description='Full path to map yaml file to load')
79 
80  declare_use_sim_time_cmd = DeclareLaunchArgument(
81  'use_sim_time',
82  default_value='false',
83  description='Use simulation (Gazebo) clock if true')
84 
85  declare_params_file_cmd = DeclareLaunchArgument(
86  'params_file',
87  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
88  description='Full path to the ROS2 parameters file to use for all launched nodes')
89 
90  declare_autostart_cmd = DeclareLaunchArgument(
91  'autostart', default_value='true',
92  description='Automatically startup the nav2 stack')
93 
94  declare_use_composition_cmd = DeclareLaunchArgument(
95  'use_composition', default_value='False',
96  description='Use composed bringup if True')
97 
98  declare_container_name_cmd = DeclareLaunchArgument(
99  'container_name', default_value='nav2_container',
100  description='the name of conatiner that nodes will load in if use composition')
101 
102  declare_use_respawn_cmd = DeclareLaunchArgument(
103  'use_respawn', default_value='False',
104  description='Whether to respawn if a node crashes. Applied when composition is disabled.')
105 
106  declare_log_level_cmd = DeclareLaunchArgument(
107  'log_level', default_value='info',
108  description='log level')
109 
110  load_nodes = GroupAction(
111  condition=IfCondition(PythonExpression(['not ', use_composition])),
112  actions=[
113  Node(
114  package='nav2_map_server',
115  executable='map_server',
116  name='map_server',
117  output='screen',
118  respawn=use_respawn,
119  respawn_delay=2.0,
120  parameters=[configured_params],
121  arguments=['--ros-args', '--log-level', log_level],
122  remappings=remappings),
123  Node(
124  package='nav2_amcl',
125  executable='amcl',
126  name='amcl',
127  output='screen',
128  respawn=use_respawn,
129  respawn_delay=2.0,
130  parameters=[configured_params],
131  arguments=['--ros-args', '--log-level', log_level],
132  remappings=remappings),
133  Node(
134  package='nav2_lifecycle_manager',
135  executable='lifecycle_manager',
136  name='lifecycle_manager_localization',
137  output='screen',
138  arguments=['--ros-args', '--log-level', log_level],
139  parameters=[{'use_sim_time': use_sim_time},
140  {'autostart': autostart},
141  {'node_names': lifecycle_nodes}])
142  ]
143  )
144 
145  load_composable_nodes = LoadComposableNodes(
146  condition=IfCondition(use_composition),
147  target_container=container_name_full,
148  composable_node_descriptions=[
149  ComposableNode(
150  package='nav2_map_server',
151  plugin='nav2_map_server::MapServer',
152  name='map_server',
153  parameters=[configured_params],
154  remappings=remappings),
155  ComposableNode(
156  package='nav2_amcl',
157  plugin='nav2_amcl::AmclNode',
158  name='amcl',
159  parameters=[configured_params],
160  remappings=remappings),
161  ComposableNode(
162  package='nav2_lifecycle_manager',
163  plugin='nav2_lifecycle_manager::LifecycleManager',
164  name='lifecycle_manager_localization',
165  parameters=[{'use_sim_time': use_sim_time,
166  'autostart': autostart,
167  'node_names': lifecycle_nodes}]),
168  ],
169  )
170 
171  # Create the launch description and populate
172  ld = LaunchDescription()
173 
174  # Set environment variables
175  ld.add_action(stdout_linebuf_envvar)
176 
177  # Declare the launch options
178  ld.add_action(declare_namespace_cmd)
179  ld.add_action(declare_map_yaml_cmd)
180  ld.add_action(declare_use_sim_time_cmd)
181  ld.add_action(declare_params_file_cmd)
182  ld.add_action(declare_autostart_cmd)
183  ld.add_action(declare_use_composition_cmd)
184  ld.add_action(declare_container_name_cmd)
185  ld.add_action(declare_use_respawn_cmd)
186  ld.add_action(declare_log_level_cmd)
187 
188  # Add the actions to launch all of the localiztion nodes
189  ld.add_action(load_nodes)
190  ld.add_action(load_composable_nodes)
191 
192  return ld