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, SetParameter
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 use_sim_time = LaunchConfiguration(
'use_sim_time')
35 autostart = LaunchConfiguration(
'autostart')
36 params_file = LaunchConfiguration(
'params_file')
37 use_composition = LaunchConfiguration(
'use_composition')
38 container_name = LaunchConfiguration(
'container_name')
39 container_name_full = (namespace,
'/', container_name)
40 use_respawn = LaunchConfiguration(
'use_respawn')
41 log_level = LaunchConfiguration(
'log_level')
62 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
65 param_substitutions = {
'autostart': autostart}
67 configured_params = ParameterFile(
69 source_file=params_file,
71 param_rewrites=param_substitutions,
77 stdout_linebuf_envvar = SetEnvironmentVariable(
78 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
81 declare_namespace_cmd = DeclareLaunchArgument(
82 'namespace', default_value=
'', description=
'Top-level namespace'
85 declare_use_sim_time_cmd = DeclareLaunchArgument(
87 default_value=
'false',
88 description=
'Use simulation (Gazebo) clock if true',
91 declare_params_file_cmd = DeclareLaunchArgument(
93 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
94 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
97 declare_autostart_cmd = DeclareLaunchArgument(
100 description=
'Automatically startup the nav2 stack',
103 declare_use_composition_cmd = DeclareLaunchArgument(
105 default_value=
'False',
106 description=
'Use composed bringup if True',
109 declare_container_name_cmd = DeclareLaunchArgument(
111 default_value=
'nav2_container',
112 description=
'the name of conatiner that nodes will load in if use composition',
115 declare_use_respawn_cmd = DeclareLaunchArgument(
117 default_value=
'False',
118 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
121 declare_log_level_cmd = DeclareLaunchArgument(
122 'log_level', default_value=
'info', description=
'log level'
125 load_nodes = GroupAction(
126 condition=IfCondition(PythonExpression([
'not ', use_composition])),
128 SetParameter(
'use_sim_time', use_sim_time),
130 package=
'nav2_controller',
131 executable=
'controller_server',
135 parameters=[configured_params],
136 arguments=[
'--ros-args',
'--log-level', log_level],
137 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
140 package=
'nav2_smoother',
141 executable=
'smoother_server',
142 name=
'smoother_server',
146 parameters=[configured_params],
147 arguments=[
'--ros-args',
'--log-level', log_level],
148 remappings=remappings,
151 package=
'nav2_planner',
152 executable=
'planner_server',
153 name=
'planner_server',
157 parameters=[configured_params],
158 arguments=[
'--ros-args',
'--log-level', log_level],
159 remappings=remappings,
162 package=
'nav2_route',
163 executable=
'route_server',
168 parameters=[configured_params],
169 arguments=[
'--ros-args',
'--log-level', log_level],
170 remappings=remappings,
173 package=
'nav2_behaviors',
174 executable=
'behavior_server',
175 name=
'behavior_server',
179 parameters=[configured_params],
180 arguments=[
'--ros-args',
'--log-level', log_level],
181 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
184 package=
'nav2_bt_navigator',
185 executable=
'bt_navigator',
190 parameters=[configured_params],
191 arguments=[
'--ros-args',
'--log-level', log_level],
192 remappings=remappings,
195 package=
'nav2_waypoint_follower',
196 executable=
'waypoint_follower',
197 name=
'waypoint_follower',
201 parameters=[configured_params],
202 arguments=[
'--ros-args',
'--log-level', log_level],
203 remappings=remappings,
206 package=
'nav2_velocity_smoother',
207 executable=
'velocity_smoother',
208 name=
'velocity_smoother',
212 parameters=[configured_params],
213 arguments=[
'--ros-args',
'--log-level', log_level],
214 remappings=remappings
215 + [(
'cmd_vel',
'cmd_vel_nav')],
218 package=
'nav2_collision_monitor',
219 executable=
'collision_monitor',
220 name=
'collision_monitor',
224 parameters=[configured_params],
225 arguments=[
'--ros-args',
'--log-level', log_level],
226 remappings=remappings,
229 package=
'opennav_docking',
230 executable=
'opennav_docking',
231 name=
'docking_server',
235 parameters=[configured_params],
236 arguments=[
'--ros-args',
'--log-level', log_level],
237 remappings=remappings,
240 package=
'nav2_lifecycle_manager',
241 executable=
'lifecycle_manager',
242 name=
'lifecycle_manager_navigation',
244 arguments=[
'--ros-args',
'--log-level', log_level],
245 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
250 load_composable_nodes = GroupAction(
251 condition=IfCondition(use_composition),
253 SetParameter(
'use_sim_time', use_sim_time),
255 target_container=container_name_full,
256 composable_node_descriptions=[
258 package=
'nav2_controller',
259 plugin=
'nav2_controller::ControllerServer',
260 name=
'controller_server',
261 parameters=[configured_params],
262 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
265 package=
'nav2_smoother',
266 plugin=
'nav2_smoother::SmootherServer',
267 name=
'smoother_server',
268 parameters=[configured_params],
269 remappings=remappings,
272 package=
'nav2_planner',
273 plugin=
'nav2_planner::PlannerServer',
274 name=
'planner_server',
275 parameters=[configured_params],
276 remappings=remappings,
279 package=
'nav2_route',
280 plugin=
'nav2_route::RouteServer',
282 parameters=[configured_params],
283 remappings=remappings,
286 package=
'nav2_behaviors',
287 plugin=
'behavior_server::BehaviorServer',
288 name=
'behavior_server',
289 parameters=[configured_params],
290 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
293 package=
'nav2_bt_navigator',
294 plugin=
'nav2_bt_navigator::BtNavigator',
296 parameters=[configured_params],
297 remappings=remappings,
300 package=
'nav2_waypoint_follower',
301 plugin=
'nav2_waypoint_follower::WaypointFollower',
302 name=
'waypoint_follower',
303 parameters=[configured_params],
304 remappings=remappings,
307 package=
'nav2_velocity_smoother',
308 plugin=
'nav2_velocity_smoother::VelocitySmoother',
309 name=
'velocity_smoother',
310 parameters=[configured_params],
311 remappings=remappings
312 + [(
'cmd_vel',
'cmd_vel_nav')],
315 package=
'nav2_collision_monitor',
316 plugin=
'nav2_collision_monitor::CollisionMonitor',
317 name=
'collision_monitor',
318 parameters=[configured_params],
319 remappings=remappings,
322 package=
'opennav_docking',
323 plugin=
'opennav_docking::DockingServer',
324 name=
'docking_server',
325 parameters=[configured_params],
326 remappings=remappings,
329 package=
'nav2_lifecycle_manager',
330 plugin=
'nav2_lifecycle_manager::LifecycleManager',
331 name=
'lifecycle_manager_navigation',
333 {
'autostart': autostart,
'node_names': lifecycle_nodes}
342 ld = LaunchDescription()
345 ld.add_action(stdout_linebuf_envvar)
348 ld.add_action(declare_namespace_cmd)
349 ld.add_action(declare_use_sim_time_cmd)
350 ld.add_action(declare_params_file_cmd)
351 ld.add_action(declare_autostart_cmd)
352 ld.add_action(declare_use_composition_cmd)
353 ld.add_action(declare_container_name_cmd)
354 ld.add_action(declare_use_respawn_cmd)
355 ld.add_action(declare_log_level_cmd)
357 ld.add_action(load_nodes)
358 ld.add_action(load_composable_nodes)