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')
61 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
64 param_substitutions = {
'autostart': autostart}
66 configured_params = ParameterFile(
68 source_file=params_file,
70 param_rewrites=param_substitutions,
76 stdout_linebuf_envvar = SetEnvironmentVariable(
77 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
80 declare_namespace_cmd = DeclareLaunchArgument(
81 'namespace', default_value=
'', description=
'Top-level namespace'
84 declare_use_sim_time_cmd = DeclareLaunchArgument(
86 default_value=
'false',
87 description=
'Use simulation (Gazebo) clock if true',
90 declare_params_file_cmd = DeclareLaunchArgument(
92 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
93 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
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 conatiner 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_behaviors',
162 executable=
'behavior_server',
163 name=
'behavior_server',
167 parameters=[configured_params],
168 arguments=[
'--ros-args',
'--log-level', log_level],
169 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
172 package=
'nav2_bt_navigator',
173 executable=
'bt_navigator',
178 parameters=[configured_params],
179 arguments=[
'--ros-args',
'--log-level', log_level],
180 remappings=remappings,
183 package=
'nav2_waypoint_follower',
184 executable=
'waypoint_follower',
185 name=
'waypoint_follower',
189 parameters=[configured_params],
190 arguments=[
'--ros-args',
'--log-level', log_level],
191 remappings=remappings,
194 package=
'nav2_velocity_smoother',
195 executable=
'velocity_smoother',
196 name=
'velocity_smoother',
200 parameters=[configured_params],
201 arguments=[
'--ros-args',
'--log-level', log_level],
202 remappings=remappings
203 + [(
'cmd_vel',
'cmd_vel_nav')],
206 package=
'nav2_collision_monitor',
207 executable=
'collision_monitor',
208 name=
'collision_monitor',
212 parameters=[configured_params],
213 arguments=[
'--ros-args',
'--log-level', log_level],
214 remappings=remappings,
217 package=
'opennav_docking',
218 executable=
'opennav_docking',
219 name=
'docking_server',
223 parameters=[configured_params],
224 arguments=[
'--ros-args',
'--log-level', log_level],
225 remappings=remappings,
228 package=
'nav2_lifecycle_manager',
229 executable=
'lifecycle_manager',
230 name=
'lifecycle_manager_navigation',
232 arguments=[
'--ros-args',
'--log-level', log_level],
233 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
238 load_composable_nodes = GroupAction(
239 condition=IfCondition(use_composition),
241 SetParameter(
'use_sim_time', use_sim_time),
243 target_container=container_name_full,
244 composable_node_descriptions=[
246 package=
'nav2_controller',
247 plugin=
'nav2_controller::ControllerServer',
248 name=
'controller_server',
249 parameters=[configured_params],
250 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
253 package=
'nav2_smoother',
254 plugin=
'nav2_smoother::SmootherServer',
255 name=
'smoother_server',
256 parameters=[configured_params],
257 remappings=remappings,
260 package=
'nav2_planner',
261 plugin=
'nav2_planner::PlannerServer',
262 name=
'planner_server',
263 parameters=[configured_params],
264 remappings=remappings,
267 package=
'nav2_behaviors',
268 plugin=
'behavior_server::BehaviorServer',
269 name=
'behavior_server',
270 parameters=[configured_params],
271 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')],
274 package=
'nav2_bt_navigator',
275 plugin=
'nav2_bt_navigator::BtNavigator',
277 parameters=[configured_params],
278 remappings=remappings,
281 package=
'nav2_waypoint_follower',
282 plugin=
'nav2_waypoint_follower::WaypointFollower',
283 name=
'waypoint_follower',
284 parameters=[configured_params],
285 remappings=remappings,
288 package=
'nav2_velocity_smoother',
289 plugin=
'nav2_velocity_smoother::VelocitySmoother',
290 name=
'velocity_smoother',
291 parameters=[configured_params],
292 remappings=remappings
293 + [(
'cmd_vel',
'cmd_vel_nav')],
296 package=
'nav2_collision_monitor',
297 plugin=
'nav2_collision_monitor::CollisionMonitor',
298 name=
'collision_monitor',
299 parameters=[configured_params],
300 remappings=remappings,
303 package=
'opennav_docking',
304 plugin=
'opennav_docking::DockingServer',
305 name=
'docking_server',
306 parameters=[configured_params],
307 remappings=remappings,
310 package=
'nav2_lifecycle_manager',
311 plugin=
'nav2_lifecycle_manager::LifecycleManager',
312 name=
'lifecycle_manager_navigation',
314 {
'autostart': autostart,
'node_names': lifecycle_nodes}
323 ld = LaunchDescription()
326 ld.add_action(stdout_linebuf_envvar)
329 ld.add_action(declare_namespace_cmd)
330 ld.add_action(declare_use_sim_time_cmd)
331 ld.add_action(declare_params_file_cmd)
332 ld.add_action(declare_autostart_cmd)
333 ld.add_action(declare_use_composition_cmd)
334 ld.add_action(declare_container_name_cmd)
335 ld.add_action(declare_use_respawn_cmd)
336 ld.add_action(declare_log_level_cmd)
338 ld.add_action(load_nodes)
339 ld.add_action(load_composable_nodes)