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')
59 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
62 param_substitutions = {
'autostart': autostart}
64 yaml_substitutions = {
65 'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
66 'SPEED_ZONE_ENABLED': use_speed_zones,
77 configured_params = ParameterFile(
79 source_file=params_file,
81 param_rewrites=param_substitutions,
82 value_rewrites=yaml_substitutions,
88 stdout_linebuf_envvar = SetEnvironmentVariable(
89 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
92 declare_namespace_cmd = DeclareLaunchArgument(
93 'namespace', default_value=
'', description=
'Top-level namespace'
96 declare_use_sim_time_cmd = DeclareLaunchArgument(
98 default_value=
'false',
99 description=
'Use simulation (Gazebo) clock if true',
102 declare_params_file_cmd = DeclareLaunchArgument(
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',
108 declare_graph_file_cmd = DeclareLaunchArgument(
110 default_value=
'', description=
'Path to the graph file to load'
113 declare_autostart_cmd = DeclareLaunchArgument(
115 default_value=
'true',
116 description=
'Automatically startup the nav2 stack',
119 declare_use_composition_cmd = DeclareLaunchArgument(
121 default_value=
'False',
122 description=
'Use composed bringup if True',
125 declare_container_name_cmd = DeclareLaunchArgument(
127 default_value=
'nav2_container',
128 description=
'the name of container that nodes will load in if use composition',
131 declare_use_respawn_cmd = DeclareLaunchArgument(
133 default_value=
'False',
134 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
137 declare_log_level_cmd = DeclareLaunchArgument(
138 'log_level', default_value=
'info', description=
'log level'
141 declare_use_keepout_zones_cmd = DeclareLaunchArgument(
142 'use_keepout_zones', default_value=
'True',
143 description=
'Whether to enable keepout zones or not'
146 declare_use_speed_zones_cmd = DeclareLaunchArgument(
147 'use_speed_zones', default_value=
'True',
148 description=
'Whether to enable speed zones or not'
151 load_nodes = GroupAction(
152 condition=IfCondition(PythonExpression([
'not ', use_composition])),
154 SetParameter(
'use_sim_time', use_sim_time),
155 PushROSNamespace(namespace=namespace),
157 package=
'nav2_controller',
158 executable=
'controller_server',
162 parameters=[configured_params],
163 arguments=[
'--ros-args',
'--log-level', log_level],
164 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
167 package=
'nav2_smoother',
168 executable=
'smoother_server',
169 name=
'smoother_server',
173 parameters=[configured_params],
174 arguments=[
'--ros-args',
'--log-level', log_level],
175 remappings=remappings,
178 package=
'nav2_planner',
179 executable=
'planner_server',
180 name=
'planner_server',
184 parameters=[configured_params],
185 arguments=[
'--ros-args',
'--log-level', log_level],
186 remappings=remappings,
189 package=
'nav2_route',
190 executable=
'route_server',
195 parameters=[configured_params, {
'graph_filepath': graph_filepath}],
196 arguments=[
'--ros-args',
'--log-level', log_level],
197 remappings=remappings),
199 package=
'nav2_behaviors',
200 executable=
'behavior_server',
201 name=
'behavior_server',
205 parameters=[configured_params],
206 arguments=[
'--ros-args',
'--log-level', log_level],
207 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
210 package=
'nav2_bt_navigator',
211 executable=
'bt_navigator',
216 parameters=[configured_params],
217 arguments=[
'--ros-args',
'--log-level', log_level],
218 remappings=remappings,
221 package=
'nav2_waypoint_follower',
222 executable=
'waypoint_follower',
223 name=
'waypoint_follower',
227 parameters=[configured_params],
228 arguments=[
'--ros-args',
'--log-level', log_level],
229 remappings=remappings,
232 package=
'nav2_velocity_smoother',
233 executable=
'velocity_smoother',
234 name=
'velocity_smoother',
238 parameters=[configured_params],
239 arguments=[
'--ros-args',
'--log-level', log_level],
240 remappings=remappings
241 + [(
'cmd_vel',
'cmd_vel_nav')],
244 package=
'nav2_collision_monitor',
245 executable=
'collision_monitor',
246 name=
'collision_monitor',
250 parameters=[configured_params],
251 arguments=[
'--ros-args',
'--log-level', log_level],
252 remappings=remappings,
255 package=
'opennav_docking',
256 executable=
'opennav_docking',
257 name=
'docking_server',
261 parameters=[configured_params],
262 arguments=[
'--ros-args',
'--log-level', log_level],
263 remappings=remappings,
266 package=
'opennav_following',
267 executable=
'opennav_following',
268 name=
'following_server',
272 parameters=[configured_params],
273 arguments=[
'--ros-args',
'--log-level', log_level],
274 remappings=remappings,
277 package=
'nav2_lifecycle_manager',
278 executable=
'lifecycle_manager',
279 name=
'lifecycle_manager_navigation',
281 arguments=[
'--ros-args',
'--log-level', log_level],
282 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
287 load_composable_nodes = GroupAction(
288 condition=IfCondition(use_composition),
290 SetParameter(
'use_sim_time', use_sim_time),
291 PushROSNamespace(namespace=namespace),
293 target_container=container_name_full,
294 composable_node_descriptions=[
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')],
303 package=
'nav2_smoother',
304 plugin=
'nav2_smoother::SmootherServer',
305 name=
'smoother_server',
306 parameters=[configured_params],
307 remappings=remappings,
310 package=
'nav2_planner',
311 plugin=
'nav2_planner::PlannerServer',
312 name=
'planner_server',
313 parameters=[configured_params],
314 remappings=remappings,
317 package=
'nav2_route',
318 plugin=
'nav2_route::RouteServer',
320 parameters=[configured_params, {
'graph_filepath': graph_filepath}],
321 remappings=remappings),
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')],
330 package=
'nav2_bt_navigator',
331 plugin=
'nav2_bt_navigator::BtNavigator',
333 parameters=[configured_params],
334 remappings=remappings,
337 package=
'nav2_waypoint_follower',
338 plugin=
'nav2_waypoint_follower::WaypointFollower',
339 name=
'waypoint_follower',
340 parameters=[configured_params],
341 remappings=remappings,
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')],
352 package=
'nav2_collision_monitor',
353 plugin=
'nav2_collision_monitor::CollisionMonitor',
354 name=
'collision_monitor',
355 parameters=[configured_params],
356 remappings=remappings,
359 package=
'opennav_docking',
360 plugin=
'opennav_docking::DockingServer',
361 name=
'docking_server',
362 parameters=[configured_params],
363 remappings=remappings,
366 package=
'opennav_following',
367 plugin=
'opennav_following::FollowingServer',
368 name=
'following_server',
369 parameters=[configured_params],
370 remappings=remappings,
373 package=
'nav2_lifecycle_manager',
374 plugin=
'nav2_lifecycle_manager::LifecycleManager',
375 name=
'lifecycle_manager_navigation',
377 {
'autostart': autostart,
'node_names': lifecycle_nodes}
386 ld = LaunchDescription()
389 ld.add_action(stdout_linebuf_envvar)
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)
404 ld.add_action(load_nodes)
405 ld.add_action(load_composable_nodes)