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 LaunchConfiguration, PythonExpression
22 from launch_ros.actions
import LoadComposableNodes, Node, SetParameter
23 from launch_ros.descriptions
import ComposableNode, ParameterFile
27 def generate_launch_description() -> LaunchDescription:
29 bringup_dir = get_package_share_directory(
'nav2_bringup')
31 namespace = LaunchConfiguration(
'namespace')
32 keepout_mask_yaml_file = LaunchConfiguration(
'keepout_mask')
33 use_sim_time = LaunchConfiguration(
'use_sim_time')
34 autostart = LaunchConfiguration(
'autostart')
35 params_file = LaunchConfiguration(
'params_file')
36 use_composition = LaunchConfiguration(
'use_composition')
37 container_name = LaunchConfiguration(
'container_name')
38 container_name_full = (namespace,
'/', container_name)
39 use_respawn = LaunchConfiguration(
'use_respawn')
40 use_keepout_zones = LaunchConfiguration(
'use_keepout_zones')
41 log_level = LaunchConfiguration(
'log_level')
43 lifecycle_nodes = [
'keepout_filter_mask_server',
'keepout_costmap_filter_info_server']
46 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
48 yaml_substitutions = {
49 'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
52 configured_params = ParameterFile(
54 source_file=params_file,
57 value_rewrites=yaml_substitutions,
63 stdout_linebuf_envvar = SetEnvironmentVariable(
64 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
67 declare_namespace_cmd = DeclareLaunchArgument(
68 'namespace', default_value=
'', description=
'Top-level namespace'
71 declare_keepout_mask_yaml_cmd = DeclareLaunchArgument(
74 description=
'Full path to keepout mask yaml file to load',
77 declare_use_sim_time_cmd = DeclareLaunchArgument(
79 default_value=
'false',
80 description=
'Use simulation (Gazebo) clock if true',
83 declare_params_file_cmd = DeclareLaunchArgument(
85 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
86 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
89 declare_use_composition_cmd = DeclareLaunchArgument(
91 default_value=
'False',
92 description=
'Use composed bringup if True',
95 declare_container_name_cmd = DeclareLaunchArgument(
97 default_value=
'nav2_container',
98 description=
'the name of container that nodes will load in if use composition',
101 declare_use_respawn_cmd = DeclareLaunchArgument(
103 default_value=
'False',
104 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
107 declare_use_keepout_zones_cmd = DeclareLaunchArgument(
108 'use_keepout_zones', default_value=
'True',
109 description=
'Whether to enable keepout zones or not'
112 declare_log_level_cmd = DeclareLaunchArgument(
113 'log_level', default_value=
'info', description=
'log level'
116 load_nodes = GroupAction(
117 condition=IfCondition(PythonExpression([
'not ', use_composition])),
119 SetParameter(
'use_sim_time', use_sim_time),
121 condition=IfCondition(use_keepout_zones),
122 package=
'nav2_map_server',
123 executable=
'map_server',
124 name=
'keepout_filter_mask_server',
128 parameters=[configured_params, {
'yaml_filename': keepout_mask_yaml_file}],
129 arguments=[
'--ros-args',
'--log-level', log_level],
130 remappings=remappings,
133 condition=IfCondition(use_keepout_zones),
134 package=
'nav2_map_server',
135 executable=
'costmap_filter_info_server',
136 name=
'keepout_costmap_filter_info_server',
140 parameters=[configured_params],
141 arguments=[
'--ros-args',
'--log-level', log_level],
142 remappings=remappings,
145 package=
'nav2_lifecycle_manager',
146 executable=
'lifecycle_manager',
147 name=
'lifecycle_manager_keepout_zone',
149 arguments=[
'--ros-args',
'--log-level', log_level],
150 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
159 load_composable_nodes = GroupAction(
160 condition=IfCondition(use_composition),
162 SetParameter(
'use_sim_time', use_sim_time),
164 target_container=container_name_full,
165 condition=IfCondition(use_keepout_zones),
166 composable_node_descriptions=[
168 package=
'nav2_map_server',
169 plugin=
'nav2_map_server::MapServer',
170 name=
'keepout_filter_mask_server',
173 {
'yaml_filename': keepout_mask_yaml_file}
175 remappings=remappings,
178 package=
'nav2_map_server',
179 plugin=
'nav2_map_server::CostmapFilterInfoServer',
180 name=
'keepout_costmap_filter_info_server',
181 parameters=[configured_params],
182 remappings=remappings,
188 target_container=container_name_full,
189 composable_node_descriptions=[
191 package=
'nav2_lifecycle_manager',
192 plugin=
'nav2_lifecycle_manager::LifecycleManager',
193 name=
'lifecycle_manager_keepout_zone',
195 {
'autostart': autostart,
'node_names': lifecycle_nodes}
204 ld = LaunchDescription()
207 ld.add_action(stdout_linebuf_envvar)
210 ld.add_action(declare_namespace_cmd)
211 ld.add_action(declare_keepout_mask_yaml_cmd)
212 ld.add_action(declare_use_sim_time_cmd)
213 ld.add_action(declare_params_file_cmd)
214 ld.add_action(declare_use_composition_cmd)
215 ld.add_action(declare_container_name_cmd)
216 ld.add_action(declare_use_respawn_cmd)
217 ld.add_action(declare_use_keepout_zones_cmd)
218 ld.add_action(declare_log_level_cmd)
221 ld.add_action(load_nodes)
222 ld.add_action(load_composable_nodes)