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 (EqualsSubstitution, LaunchConfiguration, NotEqualsSubstitution,
23 from launch_ros.actions
import LoadComposableNodes, Node, PushROSNamespace, SetParameter
24 from launch_ros.descriptions
import ComposableNode, ParameterFile
28 def generate_launch_description() -> LaunchDescription:
30 bringup_dir = get_package_share_directory(
'nav2_bringup')
32 namespace = LaunchConfiguration(
'namespace')
33 map_yaml_file = LaunchConfiguration(
'map')
34 use_sim_time = LaunchConfigAsBool(
'use_sim_time')
35 autostart = LaunchConfigAsBool(
'autostart')
36 params_file = LaunchConfiguration(
'params_file')
37 use_composition = LaunchConfigAsBool(
'use_composition')
38 container_name = LaunchConfiguration(
'container_name')
39 container_name_full = (namespace,
'/', container_name)
40 use_respawn = LaunchConfigAsBool(
'use_respawn')
41 log_level = LaunchConfiguration(
'log_level')
43 lifecycle_nodes = [
'map_server',
'amcl']
46 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
48 configured_params = ParameterFile(
50 source_file=params_file,
58 stdout_linebuf_envvar = SetEnvironmentVariable(
59 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
62 declare_namespace_cmd = DeclareLaunchArgument(
63 'namespace', default_value=
'', description=
'Top-level namespace'
66 declare_map_yaml_cmd = DeclareLaunchArgument(
67 'map', default_value=
'', description=
'Full path to map yaml file to load'
70 declare_use_sim_time_cmd = DeclareLaunchArgument(
72 default_value=
'false',
73 description=
'Use simulation (Gazebo) clock if true',
76 declare_params_file_cmd = DeclareLaunchArgument(
78 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
79 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
82 declare_autostart_cmd = DeclareLaunchArgument(
85 description=
'Automatically startup the nav2 stack',
88 declare_use_composition_cmd = DeclareLaunchArgument(
90 default_value=
'False',
91 description=
'Use composed bringup if True',
94 declare_container_name_cmd = DeclareLaunchArgument(
96 default_value=
'nav2_container',
97 description=
'the name of container that nodes will load in if use composition',
100 declare_use_respawn_cmd = DeclareLaunchArgument(
102 default_value=
'False',
103 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
106 declare_log_level_cmd = DeclareLaunchArgument(
107 'log_level', default_value=
'info', description=
'log level'
110 load_nodes = GroupAction(
111 condition=IfCondition(PythonExpression([
'not ', use_composition])),
113 PushROSNamespace(namespace),
114 SetParameter(
'use_sim_time', use_sim_time),
116 condition=IfCondition(
117 EqualsSubstitution(LaunchConfiguration(
'map'),
'')
119 package=
'nav2_map_server',
120 executable=
'map_server',
125 parameters=[configured_params],
126 arguments=[
'--ros-args',
'--log-level', log_level],
127 remappings=remappings,
130 condition=IfCondition(
131 NotEqualsSubstitution(LaunchConfiguration(
'map'),
'')
133 package=
'nav2_map_server',
134 executable=
'map_server',
139 parameters=[configured_params, {
'yaml_filename': map_yaml_file}],
140 arguments=[
'--ros-args',
'--log-level', log_level],
141 remappings=remappings,
150 parameters=[configured_params],
151 arguments=[
'--ros-args',
'--log-level', log_level],
152 remappings=remappings,
155 package=
'nav2_lifecycle_manager',
156 executable=
'lifecycle_manager',
157 name=
'lifecycle_manager_localization',
159 arguments=[
'--ros-args',
'--log-level', log_level],
160 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
169 load_composable_nodes = GroupAction(
170 condition=IfCondition(use_composition),
172 PushROSNamespace(namespace),
173 SetParameter(
'use_sim_time', use_sim_time),
175 target_container=container_name_full,
176 condition=IfCondition(
177 EqualsSubstitution(LaunchConfiguration(
'map'),
'')
179 composable_node_descriptions=[
181 package=
'nav2_map_server',
182 plugin=
'nav2_map_server::MapServer',
184 parameters=[configured_params],
185 remappings=remappings,
190 target_container=container_name_full,
191 condition=IfCondition(
192 NotEqualsSubstitution(LaunchConfiguration(
'map'),
'')
194 composable_node_descriptions=[
196 package=
'nav2_map_server',
197 plugin=
'nav2_map_server::MapServer',
201 {
'yaml_filename': map_yaml_file},
203 remappings=remappings,
208 target_container=container_name_full,
209 composable_node_descriptions=[
212 plugin=
'nav2_amcl::AmclNode',
214 parameters=[configured_params],
215 remappings=remappings,
218 package=
'nav2_lifecycle_manager',
219 plugin=
'nav2_lifecycle_manager::LifecycleManager',
220 name=
'lifecycle_manager_localization',
222 {
'autostart': autostart,
'node_names': lifecycle_nodes}
231 ld = LaunchDescription()
234 ld.add_action(stdout_linebuf_envvar)
237 ld.add_action(declare_namespace_cmd)
238 ld.add_action(declare_map_yaml_cmd)
239 ld.add_action(declare_use_sim_time_cmd)
240 ld.add_action(declare_params_file_cmd)
241 ld.add_action(declare_autostart_cmd)
242 ld.add_action(declare_use_composition_cmd)
243 ld.add_action(declare_container_name_cmd)
244 ld.add_action(declare_use_respawn_cmd)
245 ld.add_action(declare_log_level_cmd)
248 ld.add_action(load_nodes)
249 ld.add_action(load_composable_nodes)