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