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 use_sim_time = LaunchConfiguration(
'use_sim_time')
33 autostart = LaunchConfiguration(
'autostart')
34 graph_filepath = LaunchConfiguration(
'graph')
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 log_level = LaunchConfiguration(
'log_level')
56 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
59 param_substitutions = {
'autostart': autostart}
61 configured_params = ParameterFile(
63 source_file=params_file,
65 param_rewrites=param_substitutions,
71 stdout_linebuf_envvar = SetEnvironmentVariable(
72 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
75 declare_namespace_cmd = DeclareLaunchArgument(
76 'namespace', default_value=
'', description=
'Top-level namespace'
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_graph_file_cmd = DeclareLaunchArgument(
93 default_value=
'', description=
'Path to the graph file to load'
96 declare_autostart_cmd = DeclareLaunchArgument(
99 description=
'Automatically startup the nav2 stack',
102 declare_use_composition_cmd = DeclareLaunchArgument(
104 default_value=
'False',
105 description=
'Use composed bringup if True',
108 declare_container_name_cmd = DeclareLaunchArgument(
110 default_value=
'nav2_container',
111 description=
'the name of container that nodes will load in if use composition',
114 declare_use_respawn_cmd = DeclareLaunchArgument(
116 default_value=
'False',
117 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
120 declare_log_level_cmd = DeclareLaunchArgument(
121 'log_level', default_value=
'info', description=
'log level'
124 load_nodes = GroupAction(
125 condition=IfCondition(PythonExpression([
'not ', use_composition])),
127 SetParameter(
'use_sim_time', use_sim_time),
129 package=
'nav2_controller',
130 executable=
'controller_server',
134 parameters=[configured_params],
135 arguments=[
'--ros-args',
'--log-level', log_level],
136 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
139 package=
'nav2_smoother',
140 executable=
'smoother_server',
141 name=
'smoother_server',
145 parameters=[configured_params],
146 arguments=[
'--ros-args',
'--log-level', log_level],
147 remappings=remappings,
150 package=
'nav2_planner',
151 executable=
'planner_server',
152 name=
'planner_server',
156 parameters=[configured_params],
157 arguments=[
'--ros-args',
'--log-level', log_level],
158 remappings=remappings,
161 package=
'nav2_route',
162 executable=
'route_server',
167 parameters=[configured_params, {
'graph_filepath': graph_filepath}],
168 arguments=[
'--ros-args',
'--log-level', log_level],
169 remappings=remappings),
171 package=
'nav2_behaviors',
172 executable=
'behavior_server',
173 name=
'behavior_server',
177 parameters=[configured_params],
178 arguments=[
'--ros-args',
'--log-level', log_level],
179 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
182 package=
'nav2_bt_navigator',
183 executable=
'bt_navigator',
188 parameters=[configured_params],
189 arguments=[
'--ros-args',
'--log-level', log_level],
190 remappings=remappings,
193 package=
'nav2_waypoint_follower',
194 executable=
'waypoint_follower',
195 name=
'waypoint_follower',
199 parameters=[configured_params],
200 arguments=[
'--ros-args',
'--log-level', log_level],
201 remappings=remappings,
204 package=
'nav2_velocity_smoother',
205 executable=
'velocity_smoother',
206 name=
'velocity_smoother',
210 parameters=[configured_params],
211 arguments=[
'--ros-args',
'--log-level', log_level],
212 remappings=remappings
213 + [(
'cmd_vel',
'cmd_vel_nav')],
216 package=
'nav2_collision_monitor',
217 executable=
'collision_monitor',
218 name=
'collision_monitor',
222 parameters=[configured_params],
223 arguments=[
'--ros-args',
'--log-level', log_level],
224 remappings=remappings,
227 package=
'opennav_docking',
228 executable=
'opennav_docking',
229 name=
'docking_server',
233 parameters=[configured_params],
234 arguments=[
'--ros-args',
'--log-level', log_level],
235 remappings=remappings,
238 package=
'nav2_lifecycle_manager',
239 executable=
'lifecycle_manager',
240 name=
'lifecycle_manager_navigation',
242 arguments=[
'--ros-args',
'--log-level', log_level],
243 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
248 load_composable_nodes = GroupAction(
249 condition=IfCondition(use_composition),
251 SetParameter(
'use_sim_time', use_sim_time),
253 target_container=container_name_full,
254 composable_node_descriptions=[
256 package=
'nav2_controller',
257 plugin=
'nav2_controller::ControllerServer',
258 name=
'controller_server',
259 parameters=[configured_params],
260 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
263 package=
'nav2_smoother',
264 plugin=
'nav2_smoother::SmootherServer',
265 name=
'smoother_server',
266 parameters=[configured_params],
267 remappings=remappings,
270 package=
'nav2_planner',
271 plugin=
'nav2_planner::PlannerServer',
272 name=
'planner_server',
273 parameters=[configured_params],
274 remappings=remappings,
277 package=
'nav2_route',
278 plugin=
'nav2_route::RouteServer',
280 parameters=[configured_params, {
'graph_filepath': graph_filepath}],
281 remappings=remappings),
283 package=
'nav2_behaviors',
284 plugin=
'behavior_server::BehaviorServer',
285 name=
'behavior_server',
286 parameters=[configured_params],
287 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
290 package=
'nav2_bt_navigator',
291 plugin=
'nav2_bt_navigator::BtNavigator',
293 parameters=[configured_params],
294 remappings=remappings,
297 package=
'nav2_waypoint_follower',
298 plugin=
'nav2_waypoint_follower::WaypointFollower',
299 name=
'waypoint_follower',
300 parameters=[configured_params],
301 remappings=remappings,
304 package=
'nav2_velocity_smoother',
305 plugin=
'nav2_velocity_smoother::VelocitySmoother',
306 name=
'velocity_smoother',
307 parameters=[configured_params],
308 remappings=remappings
309 + [(
'cmd_vel',
'cmd_vel_nav')],
312 package=
'nav2_collision_monitor',
313 plugin=
'nav2_collision_monitor::CollisionMonitor',
314 name=
'collision_monitor',
315 parameters=[configured_params],
316 remappings=remappings,
319 package=
'opennav_docking',
320 plugin=
'opennav_docking::DockingServer',
321 name=
'docking_server',
322 parameters=[configured_params],
323 remappings=remappings,
326 package=
'nav2_lifecycle_manager',
327 plugin=
'nav2_lifecycle_manager::LifecycleManager',
328 name=
'lifecycle_manager_navigation',
330 {
'autostart': autostart,
'node_names': lifecycle_nodes}
339 ld = LaunchDescription()
342 ld.add_action(stdout_linebuf_envvar)
345 ld.add_action(declare_namespace_cmd)
346 ld.add_action(declare_use_sim_time_cmd)
347 ld.add_action(declare_params_file_cmd)
348 ld.add_action(declare_autostart_cmd)
349 ld.add_action(declare_graph_file_cmd)
350 ld.add_action(declare_use_composition_cmd)
351 ld.add_action(declare_container_name_cmd)
352 ld.add_action(declare_use_respawn_cmd)
353 ld.add_action(declare_log_level_cmd)
355 ld.add_action(load_nodes)
356 ld.add_action(load_composable_nodes)