Nav2 Navigation Stack - kilted  kilted
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, SetParameter
23 from launch_ros.descriptions import ComposableNode, ParameterFile
24 from nav2_common.launch import 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 = LaunchConfiguration('use_sim_time')
33  autostart = LaunchConfiguration('autostart')
34  graph_filepath = LaunchConfiguration('graph')
35  params_file = LaunchConfiguration('params_file')
36  use_composition = LaunchConfiguration('use_composition')
37  container_name = LaunchConfiguration('container_name')
38  container_name_full = (namespace, '/', container_name)
39  use_respawn = LaunchConfiguration('use_respawn')
40  log_level = LaunchConfiguration('log_level')
41 
42  lifecycle_nodes = [
43  'controller_server',
44  'smoother_server',
45  'planner_server',
46  'route_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  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
57 
58  # Create our own temporary YAML files that include substitutions
59  param_substitutions = {'autostart': autostart}
60 
61  configured_params = ParameterFile(
62  RewrittenYaml(
63  source_file=params_file,
64  root_key=namespace,
65  param_rewrites=param_substitutions,
66  convert_types=True,
67  ),
68  allow_substs=True,
69  )
70 
71  stdout_linebuf_envvar = SetEnvironmentVariable(
72  'RCUTILS_LOGGING_BUFFERED_STREAM', '1'
73  )
74 
75  declare_namespace_cmd = DeclareLaunchArgument(
76  'namespace', default_value='', description='Top-level namespace'
77  )
78 
79  declare_use_sim_time_cmd = DeclareLaunchArgument(
80  'use_sim_time',
81  default_value='false',
82  description='Use simulation (Gazebo) clock if true',
83  )
84 
85  declare_params_file_cmd = DeclareLaunchArgument(
86  'params_file',
87  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
88  description='Full path to the ROS2 parameters file to use for all launched nodes',
89  )
90 
91  declare_graph_file_cmd = DeclareLaunchArgument(
92  'graph',
93  default_value='', description='Path to the graph file to load'
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 container 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_route',
162  executable='route_server',
163  name='route_server',
164  output='screen',
165  respawn=use_respawn,
166  respawn_delay=2.0,
167  parameters=[configured_params, {'graph_filepath': graph_filepath}],
168  arguments=['--ros-args', '--log-level', log_level],
169  remappings=remappings),
170  Node(
171  package='nav2_behaviors',
172  executable='behavior_server',
173  name='behavior_server',
174  output='screen',
175  respawn=use_respawn,
176  respawn_delay=2.0,
177  parameters=[configured_params],
178  arguments=['--ros-args', '--log-level', log_level],
179  remappings=remappings + [('cmd_vel', 'cmd_vel_nav')],
180  ),
181  Node(
182  package='nav2_bt_navigator',
183  executable='bt_navigator',
184  name='bt_navigator',
185  output='screen',
186  respawn=use_respawn,
187  respawn_delay=2.0,
188  parameters=[configured_params],
189  arguments=['--ros-args', '--log-level', log_level],
190  remappings=remappings,
191  ),
192  Node(
193  package='nav2_waypoint_follower',
194  executable='waypoint_follower',
195  name='waypoint_follower',
196  output='screen',
197  respawn=use_respawn,
198  respawn_delay=2.0,
199  parameters=[configured_params],
200  arguments=['--ros-args', '--log-level', log_level],
201  remappings=remappings,
202  ),
203  Node(
204  package='nav2_velocity_smoother',
205  executable='velocity_smoother',
206  name='velocity_smoother',
207  output='screen',
208  respawn=use_respawn,
209  respawn_delay=2.0,
210  parameters=[configured_params],
211  arguments=['--ros-args', '--log-level', log_level],
212  remappings=remappings
213  + [('cmd_vel', 'cmd_vel_nav')],
214  ),
215  Node(
216  package='nav2_collision_monitor',
217  executable='collision_monitor',
218  name='collision_monitor',
219  output='screen',
220  respawn=use_respawn,
221  respawn_delay=2.0,
222  parameters=[configured_params],
223  arguments=['--ros-args', '--log-level', log_level],
224  remappings=remappings,
225  ),
226  Node(
227  package='opennav_docking',
228  executable='opennav_docking',
229  name='docking_server',
230  output='screen',
231  respawn=use_respawn,
232  respawn_delay=2.0,
233  parameters=[configured_params],
234  arguments=['--ros-args', '--log-level', log_level],
235  remappings=remappings,
236  ),
237  Node(
238  package='nav2_lifecycle_manager',
239  executable='lifecycle_manager',
240  name='lifecycle_manager_navigation',
241  output='screen',
242  arguments=['--ros-args', '--log-level', log_level],
243  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
244  ),
245  ],
246  )
247 
248  load_composable_nodes = GroupAction(
249  condition=IfCondition(use_composition),
250  actions=[
251  SetParameter('use_sim_time', use_sim_time),
252  LoadComposableNodes(
253  target_container=container_name_full,
254  composable_node_descriptions=[
255  ComposableNode(
256  package='nav2_controller',
257  plugin='nav2_controller::ControllerServer',
258  name='controller_server',
259  parameters=[configured_params],
260  remappings=remappings + [('cmd_vel', 'cmd_vel_nav')],
261  ),
262  ComposableNode(
263  package='nav2_smoother',
264  plugin='nav2_smoother::SmootherServer',
265  name='smoother_server',
266  parameters=[configured_params],
267  remappings=remappings,
268  ),
269  ComposableNode(
270  package='nav2_planner',
271  plugin='nav2_planner::PlannerServer',
272  name='planner_server',
273  parameters=[configured_params],
274  remappings=remappings,
275  ),
276  ComposableNode(
277  package='nav2_route',
278  plugin='nav2_route::RouteServer',
279  name='route_server',
280  parameters=[configured_params, {'graph_filepath': graph_filepath}],
281  remappings=remappings),
282  ComposableNode(
283  package='nav2_behaviors',
284  plugin='behavior_server::BehaviorServer',
285  name='behavior_server',
286  parameters=[configured_params],
287  remappings=remappings + [('cmd_vel', 'cmd_vel_nav')],
288  ),
289  ComposableNode(
290  package='nav2_bt_navigator',
291  plugin='nav2_bt_navigator::BtNavigator',
292  name='bt_navigator',
293  parameters=[configured_params],
294  remappings=remappings,
295  ),
296  ComposableNode(
297  package='nav2_waypoint_follower',
298  plugin='nav2_waypoint_follower::WaypointFollower',
299  name='waypoint_follower',
300  parameters=[configured_params],
301  remappings=remappings,
302  ),
303  ComposableNode(
304  package='nav2_velocity_smoother',
305  plugin='nav2_velocity_smoother::VelocitySmoother',
306  name='velocity_smoother',
307  parameters=[configured_params],
308  remappings=remappings
309  + [('cmd_vel', 'cmd_vel_nav')],
310  ),
311  ComposableNode(
312  package='nav2_collision_monitor',
313  plugin='nav2_collision_monitor::CollisionMonitor',
314  name='collision_monitor',
315  parameters=[configured_params],
316  remappings=remappings,
317  ),
318  ComposableNode(
319  package='opennav_docking',
320  plugin='opennav_docking::DockingServer',
321  name='docking_server',
322  parameters=[configured_params],
323  remappings=remappings,
324  ),
325  ComposableNode(
326  package='nav2_lifecycle_manager',
327  plugin='nav2_lifecycle_manager::LifecycleManager',
328  name='lifecycle_manager_navigation',
329  parameters=[
330  {'autostart': autostart, 'node_names': lifecycle_nodes}
331  ],
332  ),
333  ],
334  ),
335  ],
336  )
337 
338  # Create the launch description and populate
339  ld = LaunchDescription()
340 
341  # Set environment variables
342  ld.add_action(stdout_linebuf_envvar)
343 
344  # Declare the launch options
345  ld.add_action(declare_namespace_cmd)
346  ld.add_action(declare_use_sim_time_cmd)
347  ld.add_action(declare_params_file_cmd)
348  ld.add_action(declare_autostart_cmd)
349  ld.add_action(declare_graph_file_cmd)
350  ld.add_action(declare_use_composition_cmd)
351  ld.add_action(declare_container_name_cmd)
352  ld.add_action(declare_use_respawn_cmd)
353  ld.add_action(declare_log_level_cmd)
354  # Add the actions to launch all of the navigation nodes
355  ld.add_action(load_nodes)
356  ld.add_action(load_composable_nodes)
357 
358  return ld