Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
navigation_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 LaunchConfiguration, PythonExpression
22 from launch_ros.actions import LoadComposableNodes, Node, PushROSNamespace, SetParameter
23 from launch_ros.descriptions import ComposableNode, ParameterFile
24 from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml
25 
26 
27 def generate_launch_description() -> LaunchDescription:
28  # Get the launch directory
29  bringup_dir = get_package_share_directory('nav2_bringup')
30 
31  namespace = LaunchConfiguration('namespace')
32  use_sim_time = LaunchConfigAsBool('use_sim_time')
33  autostart = LaunchConfigAsBool('autostart')
34  graph_filepath = LaunchConfiguration('graph')
35  params_file = LaunchConfiguration('params_file')
36  use_composition = LaunchConfigAsBool('use_composition')
37  container_name = LaunchConfiguration('container_name')
38  container_name_full = (namespace, '/', container_name)
39  use_respawn = LaunchConfigAsBool('use_respawn')
40  log_level = LaunchConfiguration('log_level')
41  use_keepout_zones = LaunchConfigAsBool('use_keepout_zones')
42  use_speed_zones = LaunchConfigAsBool('use_speed_zones')
43 
44  lifecycle_nodes = [
45  'controller_server',
46  'smoother_server',
47  'planner_server',
48  'route_server',
49  'behavior_server',
50  'velocity_smoother',
51  'collision_monitor',
52  'bt_navigator',
53  'waypoint_follower',
54  'docking_server',
55  ]
56 
57  # Map fully qualified names to relative ones so the node's namespace can be prepended.
58  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
59 
60  # Create our own temporary YAML files that include substitutions
61  param_substitutions = {'autostart': autostart}
62 
63  yaml_substitutions = {
64  'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
65  'SPEED_ZONE_ENABLED': use_speed_zones,
66  }
67 
68  # RewrittenYaml: Adds namespace to the parameters file as a root key
69  # Note: Make sure that all frames are correctly namespaced in the parameters file
70  # Do not add namespace to topics in the parameters file, as they will be remapped
71  # by the root key only if they are not prefixed with a forward slash.
72  # e.g. 'map' will be remapped to '/<namespace>/map', but '/map' will not be remapped.
73  # IMPORTANT: to make your yaml file dynamic you can refer to humble branch under
74  # nav2_bringup/launch/bringup_launch.py to see how the parameters file is configured
75  # using ReplaceString <robot_namespace>
76  configured_params = ParameterFile(
77  RewrittenYaml(
78  source_file=params_file,
79  root_key=namespace,
80  param_rewrites=param_substitutions,
81  value_rewrites=yaml_substitutions,
82  convert_types=True,
83  ),
84  allow_substs=True,
85  )
86 
87  stdout_linebuf_envvar = SetEnvironmentVariable(
88  'RCUTILS_LOGGING_BUFFERED_STREAM', '1'
89  )
90 
91  declare_namespace_cmd = DeclareLaunchArgument(
92  'namespace', default_value='', description='Top-level namespace'
93  )
94 
95  declare_use_sim_time_cmd = DeclareLaunchArgument(
96  'use_sim_time',
97  default_value='false',
98  description='Use simulation (Gazebo) clock if true',
99  )
100 
101  declare_params_file_cmd = DeclareLaunchArgument(
102  'params_file',
103  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
104  description='Full path to the ROS2 parameters file to use for all launched nodes',
105  )
106 
107  declare_graph_file_cmd = DeclareLaunchArgument(
108  'graph',
109  default_value='', description='Path to the graph file to load'
110  )
111 
112  declare_autostart_cmd = DeclareLaunchArgument(
113  'autostart',
114  default_value='true',
115  description='Automatically startup the nav2 stack',
116  )
117 
118  declare_use_composition_cmd = DeclareLaunchArgument(
119  'use_composition',
120  default_value='False',
121  description='Use composed bringup if True',
122  )
123 
124  declare_container_name_cmd = DeclareLaunchArgument(
125  'container_name',
126  default_value='nav2_container',
127  description='the name of container that nodes will load in if use composition',
128  )
129 
130  declare_use_respawn_cmd = DeclareLaunchArgument(
131  'use_respawn',
132  default_value='False',
133  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
134  )
135 
136  declare_log_level_cmd = DeclareLaunchArgument(
137  'log_level', default_value='info', description='log level'
138  )
139 
140  declare_use_keepout_zones_cmd = DeclareLaunchArgument(
141  'use_keepout_zones', default_value='True',
142  description='Whether to enable keepout zones or not'
143  )
144 
145  declare_use_speed_zones_cmd = DeclareLaunchArgument(
146  'use_speed_zones', default_value='True',
147  description='Whether to enable speed zones or not'
148  )
149 
150  load_nodes = GroupAction(
151  condition=IfCondition(PythonExpression(['not ', use_composition])),
152  actions=[
153  SetParameter('use_sim_time', use_sim_time),
154  PushROSNamespace(namespace=namespace),
155  Node(
156  package='nav2_controller',
157  executable='controller_server',
158  output='screen',
159  respawn=use_respawn,
160  respawn_delay=2.0,
161  parameters=[configured_params],
162  arguments=['--ros-args', '--log-level', log_level],
163  remappings=remappings + [('cmd_vel', 'cmd_vel_nav')],
164  ),
165  Node(
166  package='nav2_smoother',
167  executable='smoother_server',
168  name='smoother_server',
169  output='screen',
170  respawn=use_respawn,
171  respawn_delay=2.0,
172  parameters=[configured_params],
173  arguments=['--ros-args', '--log-level', log_level],
174  remappings=remappings,
175  ),
176  Node(
177  package='nav2_planner',
178  executable='planner_server',
179  name='planner_server',
180  output='screen',
181  respawn=use_respawn,
182  respawn_delay=2.0,
183  parameters=[configured_params],
184  arguments=['--ros-args', '--log-level', log_level],
185  remappings=remappings,
186  ),
187  Node(
188  package='nav2_route',
189  executable='route_server',
190  name='route_server',
191  output='screen',
192  respawn=use_respawn,
193  respawn_delay=2.0,
194  parameters=[configured_params, {'graph_filepath': graph_filepath}],
195  arguments=['--ros-args', '--log-level', log_level],
196  remappings=remappings),
197  Node(
198  package='nav2_behaviors',
199  executable='behavior_server',
200  name='behavior_server',
201  output='screen',
202  respawn=use_respawn,
203  respawn_delay=2.0,
204  parameters=[configured_params],
205  arguments=['--ros-args', '--log-level', log_level],
206  remappings=remappings + [('cmd_vel', 'cmd_vel_nav')],
207  ),
208  Node(
209  package='nav2_bt_navigator',
210  executable='bt_navigator',
211  name='bt_navigator',
212  output='screen',
213  respawn=use_respawn,
214  respawn_delay=2.0,
215  parameters=[configured_params],
216  arguments=['--ros-args', '--log-level', log_level],
217  remappings=remappings,
218  ),
219  Node(
220  package='nav2_waypoint_follower',
221  executable='waypoint_follower',
222  name='waypoint_follower',
223  output='screen',
224  respawn=use_respawn,
225  respawn_delay=2.0,
226  parameters=[configured_params],
227  arguments=['--ros-args', '--log-level', log_level],
228  remappings=remappings,
229  ),
230  Node(
231  package='nav2_velocity_smoother',
232  executable='velocity_smoother',
233  name='velocity_smoother',
234  output='screen',
235  respawn=use_respawn,
236  respawn_delay=2.0,
237  parameters=[configured_params],
238  arguments=['--ros-args', '--log-level', log_level],
239  remappings=remappings
240  + [('cmd_vel', 'cmd_vel_nav')],
241  ),
242  Node(
243  package='nav2_collision_monitor',
244  executable='collision_monitor',
245  name='collision_monitor',
246  output='screen',
247  respawn=use_respawn,
248  respawn_delay=2.0,
249  parameters=[configured_params],
250  arguments=['--ros-args', '--log-level', log_level],
251  remappings=remappings,
252  ),
253  Node(
254  package='opennav_docking',
255  executable='opennav_docking',
256  name='docking_server',
257  output='screen',
258  respawn=use_respawn,
259  respawn_delay=2.0,
260  parameters=[configured_params],
261  arguments=['--ros-args', '--log-level', log_level],
262  remappings=remappings,
263  ),
264  Node(
265  package='nav2_lifecycle_manager',
266  executable='lifecycle_manager',
267  name='lifecycle_manager_navigation',
268  output='screen',
269  arguments=['--ros-args', '--log-level', log_level],
270  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
271  ),
272  ],
273  )
274 
275  load_composable_nodes = GroupAction(
276  condition=IfCondition(use_composition),
277  actions=[
278  SetParameter('use_sim_time', use_sim_time),
279  PushROSNamespace(namespace=namespace),
280  LoadComposableNodes(
281  target_container=container_name_full,
282  composable_node_descriptions=[
283  ComposableNode(
284  package='nav2_controller',
285  plugin='nav2_controller::ControllerServer',
286  name='controller_server',
287  parameters=[configured_params],
288  remappings=remappings + [('cmd_vel', 'cmd_vel_nav')],
289  ),
290  ComposableNode(
291  package='nav2_smoother',
292  plugin='nav2_smoother::SmootherServer',
293  name='smoother_server',
294  parameters=[configured_params],
295  remappings=remappings,
296  ),
297  ComposableNode(
298  package='nav2_planner',
299  plugin='nav2_planner::PlannerServer',
300  name='planner_server',
301  parameters=[configured_params],
302  remappings=remappings,
303  ),
304  ComposableNode(
305  package='nav2_route',
306  plugin='nav2_route::RouteServer',
307  name='route_server',
308  parameters=[configured_params, {'graph_filepath': graph_filepath}],
309  remappings=remappings),
310  ComposableNode(
311  package='nav2_behaviors',
312  plugin='behavior_server::BehaviorServer',
313  name='behavior_server',
314  parameters=[configured_params],
315  remappings=remappings + [('cmd_vel', 'cmd_vel_nav')],
316  ),
317  ComposableNode(
318  package='nav2_bt_navigator',
319  plugin='nav2_bt_navigator::BtNavigator',
320  name='bt_navigator',
321  parameters=[configured_params],
322  remappings=remappings,
323  ),
324  ComposableNode(
325  package='nav2_waypoint_follower',
326  plugin='nav2_waypoint_follower::WaypointFollower',
327  name='waypoint_follower',
328  parameters=[configured_params],
329  remappings=remappings,
330  ),
331  ComposableNode(
332  package='nav2_velocity_smoother',
333  plugin='nav2_velocity_smoother::VelocitySmoother',
334  name='velocity_smoother',
335  parameters=[configured_params],
336  remappings=remappings
337  + [('cmd_vel', 'cmd_vel_nav')],
338  ),
339  ComposableNode(
340  package='nav2_collision_monitor',
341  plugin='nav2_collision_monitor::CollisionMonitor',
342  name='collision_monitor',
343  parameters=[configured_params],
344  remappings=remappings,
345  ),
346  ComposableNode(
347  package='opennav_docking',
348  plugin='opennav_docking::DockingServer',
349  name='docking_server',
350  parameters=[configured_params],
351  remappings=remappings,
352  ),
353  ComposableNode(
354  package='nav2_lifecycle_manager',
355  plugin='nav2_lifecycle_manager::LifecycleManager',
356  name='lifecycle_manager_navigation',
357  parameters=[
358  {'autostart': autostart, 'node_names': lifecycle_nodes}
359  ],
360  ),
361  ],
362  ),
363  ],
364  )
365 
366  # Create the launch description and populate
367  ld = LaunchDescription()
368 
369  # Set environment variables
370  ld.add_action(stdout_linebuf_envvar)
371 
372  # Declare the launch options
373  ld.add_action(declare_namespace_cmd)
374  ld.add_action(declare_use_sim_time_cmd)
375  ld.add_action(declare_params_file_cmd)
376  ld.add_action(declare_autostart_cmd)
377  ld.add_action(declare_graph_file_cmd)
378  ld.add_action(declare_use_composition_cmd)
379  ld.add_action(declare_container_name_cmd)
380  ld.add_action(declare_use_respawn_cmd)
381  ld.add_action(declare_log_level_cmd)
382  ld.add_action(declare_use_keepout_zones_cmd)
383  ld.add_action(declare_use_speed_zones_cmd)
384  # Add the actions to launch all of the navigation nodes
385  ld.add_action(load_nodes)
386  ld.add_action(load_composable_nodes)
387 
388  return ld