17 from ament_index_python.packages
import get_package_share_directory
19 from launch
import LaunchDescription
20 from launch.actions
import DeclareLaunchArgument, IncludeLaunchDescription
21 from launch.conditions
import IfCondition, UnlessCondition
22 from launch.launch_description_sources
import PythonLaunchDescriptionSource
23 from launch.substitutions
import LaunchConfiguration
24 from launch_ros.actions
import Node
25 from launch_ros.descriptions
import ParameterFile
29 def generate_launch_description():
31 namespace = LaunchConfiguration(
'namespace')
32 params_file = LaunchConfiguration(
'params_file')
33 use_sim_time = LaunchConfiguration(
'use_sim_time')
34 autostart = LaunchConfiguration(
'autostart')
35 use_respawn = LaunchConfiguration(
'use_respawn')
36 log_level = LaunchConfiguration(
'log_level')
39 lifecycle_nodes = [
'map_saver']
42 bringup_dir = get_package_share_directory(
'nav2_bringup')
43 slam_toolbox_dir = get_package_share_directory(
'slam_toolbox')
44 slam_launch_file = os.path.join(slam_toolbox_dir,
'launch',
'online_sync_launch.py')
47 param_substitutions = {
48 'use_sim_time': use_sim_time}
50 configured_params = ParameterFile(
52 source_file=params_file,
54 param_rewrites=param_substitutions,
59 declare_namespace_cmd = DeclareLaunchArgument(
62 description=
'Top-level namespace')
64 declare_params_file_cmd = DeclareLaunchArgument(
66 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
67 description=
'Full path to the ROS2 parameters file to use for all launched nodes')
69 declare_use_sim_time_cmd = DeclareLaunchArgument(
72 description=
'Use simulation (Gazebo) clock if true')
74 declare_autostart_cmd = DeclareLaunchArgument(
75 'autostart', default_value=
'True',
76 description=
'Automatically startup the nav2 stack')
78 declare_use_respawn_cmd = DeclareLaunchArgument(
79 'use_respawn', default_value=
'False',
80 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.')
82 declare_log_level_cmd = DeclareLaunchArgument(
83 'log_level', default_value=
'info',
84 description=
'log level')
88 start_map_saver_server_cmd = Node(
89 package=
'nav2_map_server',
90 executable=
'map_saver_server',
94 arguments=[
'--ros-args',
'--log-level', log_level],
95 parameters=[configured_params])
97 start_lifecycle_manager_cmd = Node(
98 package=
'nav2_lifecycle_manager',
99 executable=
'lifecycle_manager',
100 name=
'lifecycle_manager_slam',
102 arguments=[
'--ros-args',
'--log-level', log_level],
103 parameters=[{
'use_sim_time': use_sim_time},
104 {
'autostart': autostart},
105 {
'node_names': lifecycle_nodes}])
110 has_slam_toolbox_params = HasNodeParams(source_file=params_file,
111 node_name=
'slam_toolbox')
113 start_slam_toolbox_cmd = IncludeLaunchDescription(
114 PythonLaunchDescriptionSource(slam_launch_file),
115 launch_arguments={
'use_sim_time': use_sim_time}.items(),
116 condition=UnlessCondition(has_slam_toolbox_params))
118 start_slam_toolbox_cmd_with_params = IncludeLaunchDescription(
119 PythonLaunchDescriptionSource(slam_launch_file),
120 launch_arguments={
'use_sim_time': use_sim_time,
121 'slam_params_file': params_file}.items(),
122 condition=IfCondition(has_slam_toolbox_params))
124 ld = LaunchDescription()
127 ld.add_action(declare_namespace_cmd)
128 ld.add_action(declare_params_file_cmd)
129 ld.add_action(declare_use_sim_time_cmd)
130 ld.add_action(declare_autostart_cmd)
131 ld.add_action(declare_use_respawn_cmd)
132 ld.add_action(declare_log_level_cmd)
135 ld.add_action(start_map_saver_server_cmd)
136 ld.add_action(start_lifecycle_manager_cmd)
139 ld.add_action(start_slam_toolbox_cmd)
140 ld.add_action(start_slam_toolbox_cmd_with_params)