17 from ament_index_python.packages
import get_package_share_directory
19 from launch
import LaunchDescription
20 from launch.actions
import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
21 from launch.conditions
import IfCondition
22 from launch.substitutions
import LaunchConfiguration, PythonExpression
23 from launch_ros.actions
import LoadComposableNodes
24 from launch_ros.actions
import Node
25 from launch_ros.descriptions
import ComposableNode, ParameterFile
29 def generate_launch_description():
31 bringup_dir = get_package_share_directory(
'nav2_bringup')
33 namespace = LaunchConfiguration(
'namespace')
34 map_yaml_file = LaunchConfiguration(
'map')
35 use_sim_time = LaunchConfiguration(
'use_sim_time')
36 autostart = LaunchConfiguration(
'autostart')
37 params_file = LaunchConfiguration(
'params_file')
38 use_composition = LaunchConfiguration(
'use_composition')
39 container_name = LaunchConfiguration(
'container_name')
40 container_name_full = (namespace,
'/', container_name)
41 use_respawn = LaunchConfiguration(
'use_respawn')
42 log_level = LaunchConfiguration(
'log_level')
44 lifecycle_nodes = [
'map_server',
'amcl']
52 remappings = [(
'/tf',
'tf'),
53 (
'/tf_static',
'tf_static')]
56 param_substitutions = {
57 'use_sim_time': use_sim_time,
58 'yaml_filename': map_yaml_file}
60 configured_params = ParameterFile(
62 source_file=params_file,
64 param_rewrites=param_substitutions,
68 stdout_linebuf_envvar = SetEnvironmentVariable(
69 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1')
71 declare_namespace_cmd = DeclareLaunchArgument(
74 description=
'Top-level namespace')
76 declare_map_yaml_cmd = DeclareLaunchArgument(
78 description=
'Full path to map yaml file to load')
80 declare_use_sim_time_cmd = DeclareLaunchArgument(
82 default_value=
'false',
83 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')
90 declare_autostart_cmd = DeclareLaunchArgument(
91 'autostart', default_value=
'true',
92 description=
'Automatically startup the nav2 stack')
94 declare_use_composition_cmd = DeclareLaunchArgument(
95 'use_composition', default_value=
'False',
96 description=
'Use composed bringup if True')
98 declare_container_name_cmd = DeclareLaunchArgument(
99 'container_name', default_value=
'nav2_container',
100 description=
'the name of conatiner that nodes will load in if use composition')
102 declare_use_respawn_cmd = DeclareLaunchArgument(
103 'use_respawn', default_value=
'False',
104 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',
108 description=
'log level')
110 load_nodes = GroupAction(
111 condition=IfCondition(PythonExpression([
'not ', use_composition])),
114 package=
'nav2_map_server',
115 executable=
'map_server',
120 parameters=[configured_params],
121 arguments=[
'--ros-args',
'--log-level', log_level],
122 remappings=remappings),
130 parameters=[configured_params],
131 arguments=[
'--ros-args',
'--log-level', log_level],
132 remappings=remappings),
134 package=
'nav2_lifecycle_manager',
135 executable=
'lifecycle_manager',
136 name=
'lifecycle_manager_localization',
138 arguments=[
'--ros-args',
'--log-level', log_level],
139 parameters=[{
'use_sim_time': use_sim_time},
140 {
'autostart': autostart},
141 {
'node_names': lifecycle_nodes}])
145 load_composable_nodes = LoadComposableNodes(
146 condition=IfCondition(use_composition),
147 target_container=container_name_full,
148 composable_node_descriptions=[
150 package=
'nav2_map_server',
151 plugin=
'nav2_map_server::MapServer',
153 parameters=[configured_params],
154 remappings=remappings),
157 plugin=
'nav2_amcl::AmclNode',
159 parameters=[configured_params],
160 remappings=remappings),
162 package=
'nav2_lifecycle_manager',
163 plugin=
'nav2_lifecycle_manager::LifecycleManager',
164 name=
'lifecycle_manager_localization',
165 parameters=[{
'use_sim_time': use_sim_time,
166 'autostart': autostart,
167 'node_names': lifecycle_nodes}]),
172 ld = LaunchDescription()
175 ld.add_action(stdout_linebuf_envvar)
178 ld.add_action(declare_namespace_cmd)
179 ld.add_action(declare_map_yaml_cmd)
180 ld.add_action(declare_use_sim_time_cmd)
181 ld.add_action(declare_params_file_cmd)
182 ld.add_action(declare_autostart_cmd)
183 ld.add_action(declare_use_composition_cmd)
184 ld.add_action(declare_container_name_cmd)
185 ld.add_action(declare_use_respawn_cmd)
186 ld.add_action(declare_log_level_cmd)
189 ld.add_action(load_nodes)
190 ld.add_action(load_composable_nodes)