17 from ament_index_python.packages
import get_package_share_directory
19 from launch
import LaunchDescription
20 from launch.actions
import (DeclareLaunchArgument, GroupAction,
21 IncludeLaunchDescription, SetEnvironmentVariable)
22 from launch.conditions
import IfCondition
23 from launch.launch_description_sources
import PythonLaunchDescriptionSource
24 from launch.substitutions
import LaunchConfiguration, PythonExpression
25 from launch_ros.actions
import Node
26 from launch_ros.actions
import PushRosNamespace
27 from launch_ros.descriptions
import ParameterFile
31 def generate_launch_description():
33 bringup_dir = get_package_share_directory(
'nav2_bringup')
34 launch_dir = os.path.join(bringup_dir,
'launch')
37 namespace = LaunchConfiguration(
'namespace')
38 use_namespace = LaunchConfiguration(
'use_namespace')
39 slam = LaunchConfiguration(
'slam')
40 map_yaml_file = LaunchConfiguration(
'map')
41 use_sim_time = LaunchConfiguration(
'use_sim_time')
42 params_file = LaunchConfiguration(
'params_file')
43 autostart = LaunchConfiguration(
'autostart')
44 use_composition = LaunchConfiguration(
'use_composition')
45 use_respawn = LaunchConfiguration(
'use_respawn')
46 log_level = LaunchConfiguration(
'log_level')
54 remappings = [(
'/tf',
'tf'),
55 (
'/tf_static',
'tf_static')]
58 param_substitutions = {
59 'use_sim_time': use_sim_time,
60 'yaml_filename': map_yaml_file}
66 params_file = ReplaceString(
67 source_file=params_file,
68 replacements={
'<robot_namespace>': (
'/', namespace)},
69 condition=IfCondition(use_namespace))
71 configured_params = ParameterFile(
73 source_file=params_file,
75 param_rewrites=param_substitutions,
79 stdout_linebuf_envvar = SetEnvironmentVariable(
80 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1')
82 declare_namespace_cmd = DeclareLaunchArgument(
85 description=
'Top-level namespace')
87 declare_use_namespace_cmd = DeclareLaunchArgument(
89 default_value=
'false',
90 description=
'Whether to apply a namespace to the navigation stack')
92 declare_slam_cmd = DeclareLaunchArgument(
94 default_value=
'False',
95 description=
'Whether run a SLAM')
97 declare_map_yaml_cmd = DeclareLaunchArgument(
99 description=
'Full path to map yaml file to load')
101 declare_use_sim_time_cmd = DeclareLaunchArgument(
103 default_value=
'false',
104 description=
'Use simulation (Gazebo) clock if true')
106 declare_params_file_cmd = DeclareLaunchArgument(
108 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
109 description=
'Full path to the ROS2 parameters file to use for all launched nodes')
111 declare_autostart_cmd = DeclareLaunchArgument(
112 'autostart', default_value=
'true',
113 description=
'Automatically startup the nav2 stack')
115 declare_use_composition_cmd = DeclareLaunchArgument(
116 'use_composition', default_value=
'True',
117 description=
'Whether to use composed bringup')
119 declare_use_respawn_cmd = DeclareLaunchArgument(
120 'use_respawn', default_value=
'False',
121 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.')
123 declare_log_level_cmd = DeclareLaunchArgument(
124 'log_level', default_value=
'info',
125 description=
'log level')
128 bringup_cmd_group = GroupAction([
130 condition=IfCondition(use_namespace),
131 namespace=namespace),
134 condition=IfCondition(use_composition),
135 name=
'nav2_container',
136 package=
'rclcpp_components',
137 executable=
'component_container_isolated',
138 parameters=[configured_params, {
'autostart': autostart}],
139 arguments=[
'--ros-args',
'--log-level', log_level],
140 remappings=remappings,
143 IncludeLaunchDescription(
144 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'slam_launch.py')),
145 condition=IfCondition(slam),
146 launch_arguments={
'namespace': namespace,
147 'use_sim_time': use_sim_time,
148 'autostart': autostart,
149 'use_respawn': use_respawn,
150 'params_file': params_file}.items()),
152 IncludeLaunchDescription(
153 PythonLaunchDescriptionSource(os.path.join(launch_dir,
154 'localization_launch.py')),
155 condition=IfCondition(PythonExpression([
'not ', slam])),
156 launch_arguments={
'namespace': namespace,
157 'map': map_yaml_file,
158 'use_sim_time': use_sim_time,
159 'autostart': autostart,
160 'params_file': params_file,
161 'use_composition': use_composition,
162 'use_respawn': use_respawn,
163 'container_name':
'nav2_container'}.items()),
165 IncludeLaunchDescription(
166 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'navigation_launch.py')),
167 launch_arguments={
'namespace': namespace,
168 'use_sim_time': use_sim_time,
169 'autostart': autostart,
170 'params_file': params_file,
171 'use_composition': use_composition,
172 'use_respawn': use_respawn,
173 'container_name':
'nav2_container'}.items()),
177 ld = LaunchDescription()
180 ld.add_action(stdout_linebuf_envvar)
183 ld.add_action(declare_namespace_cmd)
184 ld.add_action(declare_use_namespace_cmd)
185 ld.add_action(declare_slam_cmd)
186 ld.add_action(declare_map_yaml_cmd)
187 ld.add_action(declare_use_sim_time_cmd)
188 ld.add_action(declare_params_file_cmd)
189 ld.add_action(declare_autostart_cmd)
190 ld.add_action(declare_use_composition_cmd)
191 ld.add_action(declare_use_respawn_cmd)
192 ld.add_action(declare_log_level_cmd)
195 ld.add_action(bringup_cmd_group)