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
27 def generate_launch_description() -> LaunchDescription:
29 bringup_dir = get_package_share_directory(
'nav2_bringup')
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')
58 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
61 param_substitutions = {
'autostart': autostart}
63 yaml_substitutions = {
64 'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
65 'SPEED_ZONE_ENABLED': use_speed_zones,
76 configured_params = ParameterFile(
78 source_file=params_file,
80 param_rewrites=param_substitutions,
81 value_rewrites=yaml_substitutions,
87 stdout_linebuf_envvar = SetEnvironmentVariable(
88 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
91 declare_namespace_cmd = DeclareLaunchArgument(
92 'namespace', default_value=
'', description=
'Top-level namespace'
95 declare_use_sim_time_cmd = DeclareLaunchArgument(
97 default_value=
'false',
98 description=
'Use simulation (Gazebo) clock if true',
101 declare_params_file_cmd = DeclareLaunchArgument(
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',
107 declare_graph_file_cmd = DeclareLaunchArgument(
109 default_value=
'', description=
'Path to the graph file to load'
112 declare_autostart_cmd = DeclareLaunchArgument(
114 default_value=
'true',
115 description=
'Automatically startup the nav2 stack',
118 declare_use_composition_cmd = DeclareLaunchArgument(
120 default_value=
'False',
121 description=
'Use composed bringup if True',
124 declare_container_name_cmd = DeclareLaunchArgument(
126 default_value=
'nav2_container',
127 description=
'the name of container that nodes will load in if use composition',
130 declare_use_respawn_cmd = DeclareLaunchArgument(
132 default_value=
'False',
133 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
136 declare_log_level_cmd = DeclareLaunchArgument(
137 'log_level', default_value=
'info', description=
'log level'
140 declare_use_keepout_zones_cmd = DeclareLaunchArgument(
141 'use_keepout_zones', default_value=
'True',
142 description=
'Whether to enable keepout zones or not'
145 declare_use_speed_zones_cmd = DeclareLaunchArgument(
146 'use_speed_zones', default_value=
'True',
147 description=
'Whether to enable speed zones or not'
150 load_nodes = GroupAction(
151 condition=IfCondition(PythonExpression([
'not ', use_composition])),
153 SetParameter(
'use_sim_time', use_sim_time),
154 PushROSNamespace(namespace=namespace),
156 package=
'nav2_controller',
157 executable=
'controller_server',
161 parameters=[configured_params],
162 arguments=[
'--ros-args',
'--log-level', log_level],
163 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
166 package=
'nav2_smoother',
167 executable=
'smoother_server',
168 name=
'smoother_server',
172 parameters=[configured_params],
173 arguments=[
'--ros-args',
'--log-level', log_level],
174 remappings=remappings,
177 package=
'nav2_planner',
178 executable=
'planner_server',
179 name=
'planner_server',
183 parameters=[configured_params],
184 arguments=[
'--ros-args',
'--log-level', log_level],
185 remappings=remappings,
188 package=
'nav2_route',
189 executable=
'route_server',
194 parameters=[configured_params, {
'graph_filepath': graph_filepath}],
195 arguments=[
'--ros-args',
'--log-level', log_level],
196 remappings=remappings),
198 package=
'nav2_behaviors',
199 executable=
'behavior_server',
200 name=
'behavior_server',
204 parameters=[configured_params],
205 arguments=[
'--ros-args',
'--log-level', log_level],
206 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
209 package=
'nav2_bt_navigator',
210 executable=
'bt_navigator',
215 parameters=[configured_params],
216 arguments=[
'--ros-args',
'--log-level', log_level],
217 remappings=remappings,
220 package=
'nav2_waypoint_follower',
221 executable=
'waypoint_follower',
222 name=
'waypoint_follower',
226 parameters=[configured_params],
227 arguments=[
'--ros-args',
'--log-level', log_level],
228 remappings=remappings,
231 package=
'nav2_velocity_smoother',
232 executable=
'velocity_smoother',
233 name=
'velocity_smoother',
237 parameters=[configured_params],
238 arguments=[
'--ros-args',
'--log-level', log_level],
239 remappings=remappings
240 + [(
'cmd_vel',
'cmd_vel_nav')],
243 package=
'nav2_collision_monitor',
244 executable=
'collision_monitor',
245 name=
'collision_monitor',
249 parameters=[configured_params],
250 arguments=[
'--ros-args',
'--log-level', log_level],
251 remappings=remappings,
254 package=
'opennav_docking',
255 executable=
'opennav_docking',
256 name=
'docking_server',
260 parameters=[configured_params],
261 arguments=[
'--ros-args',
'--log-level', log_level],
262 remappings=remappings,
265 package=
'nav2_lifecycle_manager',
266 executable=
'lifecycle_manager',
267 name=
'lifecycle_manager_navigation',
269 arguments=[
'--ros-args',
'--log-level', log_level],
270 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
275 load_composable_nodes = GroupAction(
276 condition=IfCondition(use_composition),
278 SetParameter(
'use_sim_time', use_sim_time),
279 PushROSNamespace(namespace=namespace),
281 target_container=container_name_full,
282 composable_node_descriptions=[
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')],
291 package=
'nav2_smoother',
292 plugin=
'nav2_smoother::SmootherServer',
293 name=
'smoother_server',
294 parameters=[configured_params],
295 remappings=remappings,
298 package=
'nav2_planner',
299 plugin=
'nav2_planner::PlannerServer',
300 name=
'planner_server',
301 parameters=[configured_params],
302 remappings=remappings,
305 package=
'nav2_route',
306 plugin=
'nav2_route::RouteServer',
308 parameters=[configured_params, {
'graph_filepath': graph_filepath}],
309 remappings=remappings),
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')],
318 package=
'nav2_bt_navigator',
319 plugin=
'nav2_bt_navigator::BtNavigator',
321 parameters=[configured_params],
322 remappings=remappings,
325 package=
'nav2_waypoint_follower',
326 plugin=
'nav2_waypoint_follower::WaypointFollower',
327 name=
'waypoint_follower',
328 parameters=[configured_params],
329 remappings=remappings,
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')],
340 package=
'nav2_collision_monitor',
341 plugin=
'nav2_collision_monitor::CollisionMonitor',
342 name=
'collision_monitor',
343 parameters=[configured_params],
344 remappings=remappings,
347 package=
'opennav_docking',
348 plugin=
'opennav_docking::DockingServer',
349 name=
'docking_server',
350 parameters=[configured_params],
351 remappings=remappings,
354 package=
'nav2_lifecycle_manager',
355 plugin=
'nav2_lifecycle_manager::LifecycleManager',
356 name=
'lifecycle_manager_navigation',
358 {
'autostart': autostart,
'node_names': lifecycle_nodes}
367 ld = LaunchDescription()
370 ld.add_action(stdout_linebuf_envvar)
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)
385 ld.add_action(load_nodes)
386 ld.add_action(load_composable_nodes)