15 """This is all-in-one launch script intended for use by nav2 developers."""
19 from ament_index_python.packages
import get_package_share_directory
20 from launch
import LaunchDescription
21 from launch.actions
import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription
22 from launch.conditions
import IfCondition
23 from launch.launch_description_sources
import PythonLaunchDescriptionSource
24 from launch.substitutions
import LaunchConfiguration
25 from launch_ros.actions
import Node, SetParameter
26 from launch_ros.descriptions
import ParameterFile
30 def generate_launch_description() -> LaunchDescription:
32 bringup_dir = get_package_share_directory(
'nav2_bringup')
33 loopback_sim_dir = get_package_share_directory(
'nav2_loopback_sim')
34 launch_dir = os.path.join(bringup_dir,
'launch')
35 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
38 namespace = LaunchConfiguration(
'namespace')
39 map_yaml_file = LaunchConfiguration(
'map')
40 graph_filepath = LaunchConfiguration(
'graph')
41 params_file = LaunchConfiguration(
'params_file')
42 autostart = LaunchConfigAsBool(
'autostart')
43 use_composition = LaunchConfigAsBool(
'use_composition')
44 use_respawn = LaunchConfigAsBool(
'use_respawn')
47 rviz_config_file = LaunchConfiguration(
'rviz_config_file')
48 use_robot_state_pub = LaunchConfigAsBool(
'use_robot_state_pub')
49 use_rviz = LaunchConfigAsBool(
'use_rviz')
51 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
54 declare_namespace_cmd = DeclareLaunchArgument(
55 'namespace', default_value=
'', description=
'Top-level namespace'
58 declare_map_yaml_cmd = DeclareLaunchArgument(
60 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
63 declare_graph_file_cmd = DeclareLaunchArgument(
65 default_value=os.path.join(bringup_dir,
'graphs',
'turtlebot3_graph.geojson'),
68 declare_params_file_cmd = DeclareLaunchArgument(
70 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
71 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
74 declare_autostart_cmd = DeclareLaunchArgument(
77 description=
'Automatically startup the nav2 stack',
80 declare_use_composition_cmd = DeclareLaunchArgument(
83 description=
'Whether to use composed bringup',
86 declare_use_respawn_cmd = DeclareLaunchArgument(
88 default_value=
'False',
89 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
92 declare_rviz_config_file_cmd = DeclareLaunchArgument(
94 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_default_view.rviz'),
95 description=
'Full path to the RVIZ config file to use',
98 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
99 'use_robot_state_pub',
100 default_value=
'True',
101 description=
'Whether to start the robot state publisher',
104 declare_use_rviz_cmd = DeclareLaunchArgument(
105 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
108 urdf = os.path.join(sim_dir,
'urdf',
'turtlebot3_waffle.urdf')
109 with open(urdf,
'r')
as infp:
110 robot_description = infp.read()
112 start_robot_state_publisher_cmd = Node(
113 condition=IfCondition(use_robot_state_pub),
114 package=
'robot_state_publisher',
115 executable=
'robot_state_publisher',
116 name=
'robot_state_publisher',
120 {
'use_sim_time':
True,
'robot_description': robot_description}
122 remappings=remappings,
125 rviz_cmd = IncludeLaunchDescription(
126 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'rviz_launch.py')),
127 condition=IfCondition(use_rviz),
129 (
'namespace', namespace),
130 (
'use_sim_time',
'True'),
131 (
'rviz_config', rviz_config_file),
135 bringup_cmd = IncludeLaunchDescription(
136 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'bringup_launch.py')),
138 'namespace': namespace,
139 'map': map_yaml_file,
140 'graph': graph_filepath,
141 'use_sim_time':
'True',
142 'params_file': params_file,
143 'autostart': autostart,
144 'use_composition': use_composition,
145 'use_respawn': use_respawn,
146 'use_localization':
'False',
147 'use_keepout_zones':
'False',
148 'use_speed_zones':
'False',
152 loopback_sim_cmd = IncludeLaunchDescription(
153 PythonLaunchDescriptionSource(
154 os.path.join(loopback_sim_dir,
'loopback_simulation.launch.py')),
156 'params_file': params_file,
160 configured_params = ParameterFile(
162 source_file=params_file,
170 start_map_server = GroupAction(
172 SetParameter(
'use_sim_time',
True),
174 package=
'nav2_map_server',
175 executable=
'map_server',
180 parameters=[configured_params, {
'yaml_filename': map_yaml_file}],
181 remappings=remappings,
184 package=
'nav2_lifecycle_manager',
185 executable=
'lifecycle_manager',
186 name=
'lifecycle_manager_map_server',
190 {
'autostart': autostart}, {
'node_names': [
'map_server']}],
196 ld = LaunchDescription()
199 ld.add_action(declare_namespace_cmd)
200 ld.add_action(declare_map_yaml_cmd)
201 ld.add_action(declare_graph_file_cmd)
202 ld.add_action(declare_params_file_cmd)
203 ld.add_action(declare_autostart_cmd)
204 ld.add_action(declare_use_composition_cmd)
206 ld.add_action(declare_rviz_config_file_cmd)
207 ld.add_action(declare_use_robot_state_pub_cmd)
208 ld.add_action(declare_use_rviz_cmd)
209 ld.add_action(declare_use_respawn_cmd)
212 ld.add_action(start_robot_state_publisher_cmd)
213 ld.add_action(start_map_server)
214 ld.add_action(loopback_sim_cmd)
215 ld.add_action(rviz_cmd)
216 ld.add_action(bringup_cmd)