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