Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
bringup_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, IncludeLaunchDescription,
20  SetEnvironmentVariable)
21 from launch.conditions import IfCondition
22 from launch.launch_description_sources import PythonLaunchDescriptionSource
23 from launch.substitutions import LaunchConfiguration, PythonExpression
24 from launch_ros.actions import Node
25 from launch_ros.descriptions import ParameterFile
26 from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml
27 
28 
29 def generate_launch_description() -> LaunchDescription:
30  # Get the launch directory
31  bringup_dir = get_package_share_directory('nav2_bringup')
32  launch_dir = os.path.join(bringup_dir, 'launch')
33 
34  # Create the launch configuration variables
35  namespace = LaunchConfiguration('namespace')
36  slam = LaunchConfigAsBool('slam')
37  map_yaml_file = LaunchConfiguration('map')
38  keepout_mask_yaml_file = LaunchConfiguration('keepout_mask')
39  speed_mask_yaml_file = LaunchConfiguration('speed_mask')
40  graph_filepath = LaunchConfiguration('graph')
41  use_sim_time = LaunchConfigAsBool('use_sim_time')
42  params_file = LaunchConfiguration('params_file')
43  autostart = LaunchConfigAsBool('autostart')
44  use_composition = LaunchConfigAsBool('use_composition')
45  use_respawn = LaunchConfigAsBool('use_respawn')
46  log_level = LaunchConfiguration('log_level')
47  use_localization = LaunchConfigAsBool('use_localization')
48  use_keepout_zones = LaunchConfigAsBool('use_keepout_zones')
49  use_speed_zones = LaunchConfigAsBool('use_speed_zones')
50 
51  # Map fully qualified names to relative ones so the node's namespace can be prepended.
52  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
53 
54  yaml_substitutions = {
55  'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
56  'SPEED_ZONE_ENABLED': use_speed_zones,
57  }
58 
59  configured_params = ParameterFile(
60  RewrittenYaml(
61  source_file=params_file,
62  root_key=namespace,
63  param_rewrites={},
64  value_rewrites=yaml_substitutions,
65  convert_types=True,
66  ),
67  allow_substs=True,
68  )
69 
70  stdout_linebuf_envvar = SetEnvironmentVariable(
71  'RCUTILS_LOGGING_BUFFERED_STREAM', '1'
72  )
73 
74  declare_namespace_cmd = DeclareLaunchArgument(
75  'namespace', default_value='', description='Top-level namespace'
76  )
77 
78  declare_slam_cmd = DeclareLaunchArgument(
79  'slam', default_value='False', description='Whether run a SLAM'
80  )
81 
82  declare_map_yaml_cmd = DeclareLaunchArgument(
83  'map', default_value='', description='Full path to map yaml file to load'
84  )
85 
86  declare_keepout_mask_yaml_cmd = DeclareLaunchArgument(
87  'keepout_mask', default_value='',
88  description='Full path to keepout mask yaml file to load'
89  )
90 
91  declare_speed_mask_yaml_cmd = DeclareLaunchArgument(
92  'speed_mask', default_value='',
93  description='Full path to speed mask yaml file to load'
94  )
95 
96  declare_graph_file_cmd = DeclareLaunchArgument(
97  'graph',
98  default_value='', description='Path to the graph file to load'
99  )
100 
101  declare_use_localization_cmd = DeclareLaunchArgument(
102  'use_localization', default_value='True',
103  description='Whether to enable localization or not'
104  )
105 
106  declare_use_keepout_zones_cmd = DeclareLaunchArgument(
107  'use_keepout_zones', default_value='True',
108  description='Whether to enable keepout zones or not'
109  )
110 
111  declare_use_speed_zones_cmd = DeclareLaunchArgument(
112  'use_speed_zones', default_value='True',
113  description='Whether to enable speed zones or not'
114  )
115 
116  declare_use_sim_time_cmd = DeclareLaunchArgument(
117  'use_sim_time',
118  default_value='false',
119  description='Use simulation (Gazebo) clock if true',
120  )
121 
122  declare_params_file_cmd = DeclareLaunchArgument(
123  'params_file',
124  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
125  description='Full path to the ROS2 parameters file to use for all launched nodes',
126  )
127 
128  declare_autostart_cmd = DeclareLaunchArgument(
129  'autostart',
130  default_value='true',
131  description='Automatically startup the nav2 stack',
132  )
133 
134  declare_use_composition_cmd = DeclareLaunchArgument(
135  'use_composition',
136  default_value='True',
137  description='Whether to use composed bringup',
138  )
139 
140  declare_use_respawn_cmd = DeclareLaunchArgument(
141  'use_respawn',
142  default_value='False',
143  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
144  )
145 
146  declare_log_level_cmd = DeclareLaunchArgument(
147  'log_level', default_value='info', description='log level'
148  )
149 
150  # Specify the actions
151  bringup_cmd_group = GroupAction(
152  [
153  Node(
154  condition=IfCondition(use_composition),
155  name='nav2_container',
156  namespace=namespace,
157  package='rclcpp_components',
158  executable='component_container_isolated',
159  parameters=[configured_params, {'autostart': autostart}],
160  arguments=['--ros-args', '--log-level', log_level],
161  remappings=remappings,
162  output='screen',
163  ),
164  IncludeLaunchDescription(
165  PythonLaunchDescriptionSource(
166  os.path.join(launch_dir, 'slam_launch.py')
167  ),
168  condition=IfCondition(PythonExpression([slam, ' and ', use_localization])),
169  launch_arguments={
170  'namespace': namespace,
171  'use_sim_time': use_sim_time,
172  'autostart': autostart,
173  'use_respawn': use_respawn,
174  'params_file': params_file,
175  }.items(),
176  ),
177  IncludeLaunchDescription(
178  PythonLaunchDescriptionSource(
179  os.path.join(launch_dir, 'localization_launch.py')
180  ),
181  condition=IfCondition(PythonExpression(['not ', slam, ' and ', use_localization])),
182  launch_arguments={
183  'namespace': namespace,
184  'map': map_yaml_file,
185  'use_sim_time': use_sim_time,
186  'autostart': autostart,
187  'params_file': params_file,
188  'use_composition': use_composition,
189  'use_respawn': use_respawn,
190  'container_name': 'nav2_container',
191  }.items(),
192  ),
193 
194  IncludeLaunchDescription(
195  PythonLaunchDescriptionSource(
196  os.path.join(launch_dir, 'keepout_zone_launch.py')
197  ),
198  condition=IfCondition(use_keepout_zones),
199  launch_arguments={
200  'namespace': namespace,
201  'keepout_mask': keepout_mask_yaml_file,
202  'use_sim_time': use_sim_time,
203  'params_file': params_file,
204  'use_composition': use_composition,
205  'use_respawn': use_respawn,
206  'container_name': 'nav2_container',
207  }.items(),
208  ),
209 
210  IncludeLaunchDescription(
211  PythonLaunchDescriptionSource(
212  os.path.join(launch_dir, 'speed_zone_launch.py')
213  ),
214  condition=IfCondition(use_speed_zones),
215  launch_arguments={
216  'namespace': namespace,
217  'speed_mask': speed_mask_yaml_file,
218  'use_sim_time': use_sim_time,
219  'params_file': params_file,
220  'use_composition': use_composition,
221  'use_respawn': use_respawn,
222  'container_name': 'nav2_container',
223  }.items(),
224  ),
225 
226  IncludeLaunchDescription(
227  PythonLaunchDescriptionSource(
228  os.path.join(launch_dir, 'navigation_launch.py')
229  ),
230  launch_arguments={
231  'namespace': namespace,
232  'use_sim_time': use_sim_time,
233  'autostart': autostart,
234  'graph': graph_filepath,
235  'params_file': params_file,
236  'use_composition': use_composition,
237  'use_respawn': use_respawn,
238  'use_keepout_zones': use_keepout_zones,
239  'use_speed_zones': use_speed_zones,
240  'container_name': 'nav2_container',
241  }.items(),
242  ),
243  ]
244  )
245 
246  # Create the launch description and populate
247  ld = LaunchDescription()
248 
249  # Set environment variables
250  ld.add_action(stdout_linebuf_envvar)
251 
252  # Declare the launch options
253  ld.add_action(declare_namespace_cmd)
254  ld.add_action(declare_slam_cmd)
255  ld.add_action(declare_map_yaml_cmd)
256  ld.add_action(declare_keepout_mask_yaml_cmd)
257  ld.add_action(declare_speed_mask_yaml_cmd)
258  ld.add_action(declare_graph_file_cmd)
259  ld.add_action(declare_use_sim_time_cmd)
260  ld.add_action(declare_params_file_cmd)
261  ld.add_action(declare_autostart_cmd)
262  ld.add_action(declare_use_composition_cmd)
263  ld.add_action(declare_use_respawn_cmd)
264  ld.add_action(declare_log_level_cmd)
265  ld.add_action(declare_use_localization_cmd)
266  ld.add_action(declare_use_keepout_zones_cmd)
267  ld.add_action(declare_use_speed_zones_cmd)
268 
269  # Add the actions to launch all of the navigation nodes
270  ld.add_action(bringup_cmd_group)
271 
272  return ld