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