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, 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 = 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')
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 SetParameter(
'use_sim_time', use_sim_time),
115 condition=IfCondition(
116 EqualsSubstitution(LaunchConfiguration(
'map'),
'')
118 package=
'nav2_map_server',
119 executable=
'map_server',
124 parameters=[configured_params],
125 arguments=[
'--ros-args',
'--log-level', log_level],
126 remappings=remappings,
129 condition=IfCondition(
130 NotEqualsSubstitution(LaunchConfiguration(
'map'),
'')
132 package=
'nav2_map_server',
133 executable=
'map_server',
138 parameters=[configured_params, {
'yaml_filename': map_yaml_file}],
139 arguments=[
'--ros-args',
'--log-level', log_level],
140 remappings=remappings,
149 parameters=[configured_params],
150 arguments=[
'--ros-args',
'--log-level', log_level],
151 remappings=remappings,
154 package=
'nav2_lifecycle_manager',
155 executable=
'lifecycle_manager',
156 name=
'lifecycle_manager_localization',
158 arguments=[
'--ros-args',
'--log-level', log_level],
159 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
168 load_composable_nodes = GroupAction(
169 condition=IfCondition(use_composition),
171 SetParameter(
'use_sim_time', use_sim_time),
173 target_container=container_name_full,
174 condition=IfCondition(
175 EqualsSubstitution(LaunchConfiguration(
'map'),
'')
177 composable_node_descriptions=[
179 package=
'nav2_map_server',
180 plugin=
'nav2_map_server::MapServer',
182 parameters=[configured_params],
183 remappings=remappings,
188 target_container=container_name_full,
189 condition=IfCondition(
190 NotEqualsSubstitution(LaunchConfiguration(
'map'),
'')
192 composable_node_descriptions=[
194 package=
'nav2_map_server',
195 plugin=
'nav2_map_server::MapServer',
199 {
'yaml_filename': map_yaml_file},
201 remappings=remappings,
206 target_container=container_name_full,
207 composable_node_descriptions=[
210 plugin=
'nav2_amcl::AmclNode',
212 parameters=[configured_params],
213 remappings=remappings,
216 package=
'nav2_lifecycle_manager',
217 plugin=
'nav2_lifecycle_manager::LifecycleManager',
218 name=
'lifecycle_manager_localization',
220 {
'autostart': autostart,
'node_names': lifecycle_nodes}
229 ld = LaunchDescription()
232 ld.add_action(stdout_linebuf_envvar)
235 ld.add_action(declare_namespace_cmd)
236 ld.add_action(declare_map_yaml_cmd)
237 ld.add_action(declare_use_sim_time_cmd)
238 ld.add_action(declare_params_file_cmd)
239 ld.add_action(declare_autostart_cmd)
240 ld.add_action(declare_use_composition_cmd)
241 ld.add_action(declare_container_name_cmd)
242 ld.add_action(declare_use_respawn_cmd)
243 ld.add_action(declare_log_level_cmd)
246 ld.add_action(load_nodes)
247 ld.add_action(load_composable_nodes)