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