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