17 from ament_index_python.packages
import get_package_share_directory
19 from launch
import LaunchDescription
20 from launch.actions
import DeclareLaunchArgument, GroupAction
21 from launch.actions
import SetEnvironmentVariable
22 from launch.conditions
import IfCondition
23 from launch.substitutions
import EqualsSubstitution
24 from launch.substitutions
import LaunchConfiguration, PythonExpression
25 from launch.substitutions
import NotEqualsSubstitution
26 from launch_ros.actions
import LoadComposableNodes, SetParameter
27 from launch_ros.actions
import Node
28 from launch_ros.descriptions
import ComposableNode, ParameterFile
32 def generate_launch_description():
34 bringup_dir = get_package_share_directory(
'nav2_bringup')
36 namespace = LaunchConfiguration(
'namespace')
37 map_yaml_file = LaunchConfiguration(
'map')
38 use_sim_time = LaunchConfiguration(
'use_sim_time')
39 autostart = LaunchConfiguration(
'autostart')
40 params_file = LaunchConfiguration(
'params_file')
41 use_composition = LaunchConfiguration(
'use_composition')
42 container_name = LaunchConfiguration(
'container_name')
43 container_name_full = (namespace,
'/', container_name)
44 use_respawn = LaunchConfiguration(
'use_respawn')
45 log_level = LaunchConfiguration(
'log_level')
47 lifecycle_nodes = [
'map_server',
'amcl']
55 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
57 configured_params = ParameterFile(
59 source_file=params_file,
67 stdout_linebuf_envvar = SetEnvironmentVariable(
68 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
71 declare_namespace_cmd = DeclareLaunchArgument(
72 'namespace', default_value=
'', description=
'Top-level namespace'
75 declare_map_yaml_cmd = DeclareLaunchArgument(
76 'map', default_value=
'', description=
'Full path to map yaml file to load'
79 declare_use_sim_time_cmd = DeclareLaunchArgument(
81 default_value=
'false',
82 description=
'Use simulation (Gazebo) clock if true',
85 declare_params_file_cmd = DeclareLaunchArgument(
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',
91 declare_autostart_cmd = DeclareLaunchArgument(
94 description=
'Automatically startup the nav2 stack',
97 declare_use_composition_cmd = DeclareLaunchArgument(
99 default_value=
'False',
100 description=
'Use composed bringup if True',
103 declare_container_name_cmd = DeclareLaunchArgument(
105 default_value=
'nav2_container',
106 description=
'the name of conatiner that nodes will load in if use composition',
109 declare_use_respawn_cmd = DeclareLaunchArgument(
111 default_value=
'False',
112 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
115 declare_log_level_cmd = DeclareLaunchArgument(
116 'log_level', default_value=
'info', description=
'log level'
119 load_nodes = GroupAction(
120 condition=IfCondition(PythonExpression([
'not ', use_composition])),
122 SetParameter(
'use_sim_time', use_sim_time),
124 condition=IfCondition(
125 EqualsSubstitution(LaunchConfiguration(
'map'),
'')
127 package=
'nav2_map_server',
128 executable=
'map_server',
133 parameters=[configured_params],
134 arguments=[
'--ros-args',
'--log-level', log_level],
135 remappings=remappings,
138 condition=IfCondition(
139 NotEqualsSubstitution(LaunchConfiguration(
'map'),
'')
141 package=
'nav2_map_server',
142 executable=
'map_server',
147 parameters=[configured_params, {
'yaml_filename': map_yaml_file}],
148 arguments=[
'--ros-args',
'--log-level', log_level],
149 remappings=remappings,
158 parameters=[configured_params],
159 arguments=[
'--ros-args',
'--log-level', log_level],
160 remappings=remappings,
163 package=
'nav2_lifecycle_manager',
164 executable=
'lifecycle_manager',
165 name=
'lifecycle_manager_localization',
167 arguments=[
'--ros-args',
'--log-level', log_level],
168 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
177 load_composable_nodes = GroupAction(
178 condition=IfCondition(use_composition),
180 SetParameter(
'use_sim_time', use_sim_time),
182 target_container=container_name_full,
183 condition=IfCondition(
184 EqualsSubstitution(LaunchConfiguration(
'map'),
'')
186 composable_node_descriptions=[
188 package=
'nav2_map_server',
189 plugin=
'nav2_map_server::MapServer',
191 parameters=[configured_params],
192 remappings=remappings,
197 target_container=container_name_full,
198 condition=IfCondition(
199 NotEqualsSubstitution(LaunchConfiguration(
'map'),
'')
201 composable_node_descriptions=[
203 package=
'nav2_map_server',
204 plugin=
'nav2_map_server::MapServer',
208 {
'yaml_filename': map_yaml_file},
210 remappings=remappings,
215 target_container=container_name_full,
216 composable_node_descriptions=[
219 plugin=
'nav2_amcl::AmclNode',
221 parameters=[configured_params],
222 remappings=remappings,
225 package=
'nav2_lifecycle_manager',
226 plugin=
'nav2_lifecycle_manager::LifecycleManager',
227 name=
'lifecycle_manager_localization',
229 {
'autostart': autostart,
'node_names': lifecycle_nodes}
238 ld = LaunchDescription()
241 ld.add_action(stdout_linebuf_envvar)
244 ld.add_action(declare_namespace_cmd)
245 ld.add_action(declare_map_yaml_cmd)
246 ld.add_action(declare_use_sim_time_cmd)
247 ld.add_action(declare_params_file_cmd)
248 ld.add_action(declare_autostart_cmd)
249 ld.add_action(declare_use_composition_cmd)
250 ld.add_action(declare_container_name_cmd)
251 ld.add_action(declare_use_respawn_cmd)
252 ld.add_action(declare_log_level_cmd)
255 ld.add_action(load_nodes)
256 ld.add_action(load_composable_nodes)