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
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')
43 lifecycle_nodes = [
'controller_server',
57 remappings = [(
'/tf',
'tf'),
58 (
'/tf_static',
'tf_static')]
61 param_substitutions = {
62 'use_sim_time': use_sim_time,
63 'autostart': autostart}
65 configured_params = ParameterFile(
67 source_file=params_file,
69 param_rewrites=param_substitutions,
73 stdout_linebuf_envvar = SetEnvironmentVariable(
74 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1')
76 declare_namespace_cmd = DeclareLaunchArgument(
79 description=
'Top-level namespace')
81 declare_use_sim_time_cmd = DeclareLaunchArgument(
83 default_value=
'false',
84 description=
'Use simulation (Gazebo) clock if true')
86 declare_params_file_cmd = DeclareLaunchArgument(
88 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
89 description=
'Full path to the ROS2 parameters file to use for all launched nodes')
91 declare_autostart_cmd = DeclareLaunchArgument(
92 'autostart', default_value=
'true',
93 description=
'Automatically startup the nav2 stack')
95 declare_use_composition_cmd = DeclareLaunchArgument(
96 'use_composition', default_value=
'False',
97 description=
'Use composed bringup if True')
99 declare_container_name_cmd = DeclareLaunchArgument(
100 'container_name', default_value=
'nav2_container',
101 description=
'the name of conatiner that nodes will load in if use composition')
103 declare_use_respawn_cmd = DeclareLaunchArgument(
104 'use_respawn', default_value=
'False',
105 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.')
107 declare_log_level_cmd = DeclareLaunchArgument(
108 'log_level', default_value=
'info',
109 description=
'log level')
111 load_nodes = GroupAction(
112 condition=IfCondition(PythonExpression([
'not ', use_composition])),
115 package=
'nav2_controller',
116 executable=
'controller_server',
120 parameters=[configured_params],
121 arguments=[
'--ros-args',
'--log-level', log_level],
122 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')]),
124 package=
'nav2_smoother',
125 executable=
'smoother_server',
126 name=
'smoother_server',
130 parameters=[configured_params],
131 arguments=[
'--ros-args',
'--log-level', log_level],
132 remappings=remappings),
134 package=
'nav2_planner',
135 executable=
'planner_server',
136 name=
'planner_server',
140 parameters=[configured_params],
141 arguments=[
'--ros-args',
'--log-level', log_level],
142 remappings=remappings),
144 package=
'nav2_behaviors',
145 executable=
'behavior_server',
146 name=
'behavior_server',
150 parameters=[configured_params],
151 arguments=[
'--ros-args',
'--log-level', log_level],
152 remappings=remappings),
154 package=
'nav2_bt_navigator',
155 executable=
'bt_navigator',
160 parameters=[configured_params],
161 arguments=[
'--ros-args',
'--log-level', log_level],
162 remappings=remappings),
164 package=
'nav2_waypoint_follower',
165 executable=
'waypoint_follower',
166 name=
'waypoint_follower',
170 parameters=[configured_params],
171 arguments=[
'--ros-args',
'--log-level', log_level],
172 remappings=remappings),
174 package=
'nav2_velocity_smoother',
175 executable=
'velocity_smoother',
176 name=
'velocity_smoother',
180 parameters=[configured_params],
181 arguments=[
'--ros-args',
'--log-level', log_level],
182 remappings=remappings +
183 [(
'cmd_vel',
'cmd_vel_nav'), (
'cmd_vel_smoothed',
'cmd_vel')]),
185 package=
'nav2_lifecycle_manager',
186 executable=
'lifecycle_manager',
187 name=
'lifecycle_manager_navigation',
189 arguments=[
'--ros-args',
'--log-level', log_level],
190 parameters=[{
'use_sim_time': use_sim_time},
191 {
'autostart': autostart},
192 {
'node_names': lifecycle_nodes}]),
196 load_composable_nodes = LoadComposableNodes(
197 condition=IfCondition(use_composition),
198 target_container=container_name_full,
199 composable_node_descriptions=[
201 package=
'nav2_controller',
202 plugin=
'nav2_controller::ControllerServer',
203 name=
'controller_server',
204 parameters=[configured_params],
205 remappings=remappings + [(
'cmd_vel',
'cmd_vel_nav')]),
207 package=
'nav2_smoother',
208 plugin=
'nav2_smoother::SmootherServer',
209 name=
'smoother_server',
210 parameters=[configured_params],
211 remappings=remappings),
213 package=
'nav2_planner',
214 plugin=
'nav2_planner::PlannerServer',
215 name=
'planner_server',
216 parameters=[configured_params],
217 remappings=remappings),
219 package=
'nav2_behaviors',
220 plugin=
'behavior_server::BehaviorServer',
221 name=
'behavior_server',
222 parameters=[configured_params],
223 remappings=remappings),
225 package=
'nav2_bt_navigator',
226 plugin=
'nav2_bt_navigator::BtNavigator',
228 parameters=[configured_params],
229 remappings=remappings),
231 package=
'nav2_waypoint_follower',
232 plugin=
'nav2_waypoint_follower::WaypointFollower',
233 name=
'waypoint_follower',
234 parameters=[configured_params],
235 remappings=remappings),
237 package=
'nav2_velocity_smoother',
238 plugin=
'nav2_velocity_smoother::VelocitySmoother',
239 name=
'velocity_smoother',
240 parameters=[configured_params],
241 remappings=remappings +
242 [(
'cmd_vel',
'cmd_vel_nav'), (
'cmd_vel_smoothed',
'cmd_vel')]),
244 package=
'nav2_lifecycle_manager',
245 plugin=
'nav2_lifecycle_manager::LifecycleManager',
246 name=
'lifecycle_manager_navigation',
247 parameters=[{
'use_sim_time': use_sim_time,
248 'autostart': autostart,
249 'node_names': lifecycle_nodes}]),
254 ld = LaunchDescription()
257 ld.add_action(stdout_linebuf_envvar)
260 ld.add_action(declare_namespace_cmd)
261 ld.add_action(declare_use_sim_time_cmd)
262 ld.add_action(declare_params_file_cmd)
263 ld.add_action(declare_autostart_cmd)
264 ld.add_action(declare_use_composition_cmd)
265 ld.add_action(declare_container_name_cmd)
266 ld.add_action(declare_use_respawn_cmd)
267 ld.add_action(declare_log_level_cmd)
269 ld.add_action(load_nodes)
270 ld.add_action(load_composable_nodes)