Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
keepout_zone_launch.py
1 # Copyright (c) 2025 Leander Stephen Desouza
2 #
3 # Licensed under the Apache License, Version 2.0 (the "License");
4 # you may not use this file except in compliance with the License.
5 # You may obtain a copy of the License at
6 #
7 # http://www.apache.org/licenses/LICENSE-2.0
8 #
9 # Unless required by applicable law or agreed to in writing, software
10 # distributed under the License is distributed on an "AS IS" BASIS,
11 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 # See the License for the specific language governing permissions and
13 # limitations under the License.
14 
15 import os
16 
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
24 from nav2_common.launch import RewrittenYaml
25 
26 
27 def generate_launch_description() -> LaunchDescription:
28  # Get the launch directory
29  bringup_dir = get_package_share_directory('nav2_bringup')
30 
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')
42 
43  lifecycle_nodes = ['keepout_filter_mask_server', 'keepout_costmap_filter_info_server']
44 
45  # Map fully qualified names to relative ones so the node's namespace can be prepended.
46  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
47 
48  yaml_substitutions = {
49  'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
50  }
51 
52  configured_params = ParameterFile(
53  RewrittenYaml(
54  source_file=params_file,
55  root_key=namespace,
56  param_rewrites={},
57  value_rewrites=yaml_substitutions,
58  convert_types=True,
59  ),
60  allow_substs=True,
61  )
62 
63  stdout_linebuf_envvar = SetEnvironmentVariable(
64  'RCUTILS_LOGGING_BUFFERED_STREAM', '1'
65  )
66 
67  declare_namespace_cmd = DeclareLaunchArgument(
68  'namespace', default_value='', description='Top-level namespace'
69  )
70 
71  declare_keepout_mask_yaml_cmd = DeclareLaunchArgument(
72  'keepout_mask',
73  default_value='',
74  description='Full path to keepout mask yaml file to load',
75  )
76 
77  declare_use_sim_time_cmd = DeclareLaunchArgument(
78  'use_sim_time',
79  default_value='false',
80  description='Use simulation (Gazebo) clock if true',
81  )
82 
83  declare_params_file_cmd = DeclareLaunchArgument(
84  'params_file',
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',
87  )
88 
89  declare_use_composition_cmd = DeclareLaunchArgument(
90  'use_composition',
91  default_value='False',
92  description='Use composed bringup if True',
93  )
94 
95  declare_container_name_cmd = DeclareLaunchArgument(
96  'container_name',
97  default_value='nav2_container',
98  description='the name of container that nodes will load in if use composition',
99  )
100 
101  declare_use_respawn_cmd = DeclareLaunchArgument(
102  'use_respawn',
103  default_value='False',
104  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
105  )
106 
107  declare_use_keepout_zones_cmd = DeclareLaunchArgument(
108  'use_keepout_zones', default_value='True',
109  description='Whether to enable keepout zones or not'
110  )
111 
112  declare_log_level_cmd = DeclareLaunchArgument(
113  'log_level', default_value='info', description='log level'
114  )
115 
116  load_nodes = GroupAction(
117  condition=IfCondition(PythonExpression(['not ', use_composition])),
118  actions=[
119  SetParameter('use_sim_time', use_sim_time),
120  Node(
121  condition=IfCondition(use_keepout_zones),
122  package='nav2_map_server',
123  executable='map_server',
124  name='keepout_filter_mask_server',
125  output='screen',
126  respawn=use_respawn,
127  respawn_delay=2.0,
128  parameters=[configured_params, {'yaml_filename': keepout_mask_yaml_file}],
129  arguments=['--ros-args', '--log-level', log_level],
130  remappings=remappings,
131  ),
132  Node(
133  condition=IfCondition(use_keepout_zones),
134  package='nav2_map_server',
135  executable='costmap_filter_info_server',
136  name='keepout_costmap_filter_info_server',
137  output='screen',
138  respawn=use_respawn,
139  respawn_delay=2.0,
140  parameters=[configured_params],
141  arguments=['--ros-args', '--log-level', log_level],
142  remappings=remappings,
143  ),
144  Node(
145  package='nav2_lifecycle_manager',
146  executable='lifecycle_manager',
147  name='lifecycle_manager_keepout_zone',
148  output='screen',
149  arguments=['--ros-args', '--log-level', log_level],
150  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
151  ),
152  ],
153  )
154  # LoadComposableNode for map server twice depending if we should use the
155  # value of map from a CLI or launch default or user defined value in the
156  # yaml configuration file. They are separated since the conditions
157  # currently only work on the LoadComposableNodes commands and not on the
158  # ComposableNode node function itself
159  load_composable_nodes = GroupAction(
160  condition=IfCondition(use_composition),
161  actions=[
162  SetParameter('use_sim_time', use_sim_time),
163  LoadComposableNodes(
164  target_container=container_name_full,
165  condition=IfCondition(use_keepout_zones),
166  composable_node_descriptions=[
167  ComposableNode(
168  package='nav2_map_server',
169  plugin='nav2_map_server::MapServer',
170  name='keepout_filter_mask_server',
171  parameters=[
172  configured_params,
173  {'yaml_filename': keepout_mask_yaml_file}
174  ],
175  remappings=remappings,
176  ),
177  ComposableNode(
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,
183  ),
184  ],
185  ),
186 
187  LoadComposableNodes(
188  target_container=container_name_full,
189  composable_node_descriptions=[
190  ComposableNode(
191  package='nav2_lifecycle_manager',
192  plugin='nav2_lifecycle_manager::LifecycleManager',
193  name='lifecycle_manager_keepout_zone',
194  parameters=[
195  {'autostart': autostart, 'node_names': lifecycle_nodes}
196  ],
197  ),
198  ],
199  ),
200  ],
201  )
202 
203  # Create the launch description and populate
204  ld = LaunchDescription()
205 
206  # Set environment variables
207  ld.add_action(stdout_linebuf_envvar)
208 
209  # Declare the launch options
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)
219 
220  # Add the actions to launch all of the map modifier nodes
221  ld.add_action(load_nodes)
222  ld.add_action(load_composable_nodes)
223 
224  return ld