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 Command, 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 desc_dir = get_package_share_directory(
'nav2_minimal_tb4_description')
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',
'depot.yaml'),
61 description=
'Full path to map file to load',
64 declare_graph_file_cmd = DeclareLaunchArgument(
66 default_value=os.path.join(bringup_dir,
'graphs',
'depot_graph.geojson'),
69 declare_params_file_cmd = DeclareLaunchArgument(
71 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
72 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
75 declare_autostart_cmd = DeclareLaunchArgument(
78 description=
'Automatically startup the nav2 stack',
81 declare_use_composition_cmd = DeclareLaunchArgument(
84 description=
'Whether to use composed bringup',
87 declare_use_respawn_cmd = DeclareLaunchArgument(
89 default_value=
'False',
90 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
93 declare_rviz_config_file_cmd = DeclareLaunchArgument(
95 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_default_view.rviz'),
96 description=
'Full path to the RVIZ config file to use',
99 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
100 'use_robot_state_pub',
101 default_value=
'True',
102 description=
'Whether to start the robot state publisher',
105 declare_use_rviz_cmd = DeclareLaunchArgument(
106 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
109 sdf = os.path.join(desc_dir,
'urdf',
'standard',
'turtlebot4.urdf.xacro')
110 start_robot_state_publisher_cmd = Node(
111 condition=IfCondition(use_robot_state_pub),
112 package=
'robot_state_publisher',
113 executable=
'robot_state_publisher',
114 name=
'robot_state_publisher',
118 {
'use_sim_time':
True,
'robot_description': Command([
'xacro',
' ', sdf])}
120 remappings=remappings,
123 rviz_cmd = IncludeLaunchDescription(
124 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'rviz_launch.py')),
125 condition=IfCondition(use_rviz),
127 (
'namespace', namespace),
128 (
'use_sim_time',
'True'),
129 (
'rviz_config', rviz_config_file),
133 bringup_cmd = IncludeLaunchDescription(
134 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'bringup_launch.py')),
136 'namespace': namespace,
137 'map': map_yaml_file,
138 'graph': graph_filepath,
139 'use_sim_time':
'True',
140 'params_file': params_file,
141 'autostart': autostart,
142 'use_composition': use_composition,
143 'use_respawn': use_respawn,
144 'use_keepout_zones':
'False',
145 'use_speed_zones':
'False',
146 'use_localization':
'False',
150 loopback_sim_cmd = IncludeLaunchDescription(
151 PythonLaunchDescriptionSource(
152 os.path.join(loopback_sim_dir,
'loopback_simulation.launch.py')),
154 (
'params_file', params_file),
155 (
'scan_frame_id',
'rplidar_link'),
159 static_publisher_cmd = Node(
161 executable=
'static_transform_publisher',
163 '--x',
'0.0',
'--y',
'0.0',
'--z',
'0.0',
164 '--roll',
'0',
'--pitch',
'0',
'--yaw',
'0',
165 '--frame-id',
'base_footprint',
'--child-frame-id',
'base_link']
168 configured_params = ParameterFile(
170 source_file=params_file,
178 start_map_server = GroupAction(
180 SetParameter(
'use_sim_time',
True),
182 package=
'nav2_map_server',
183 executable=
'map_server',
188 parameters=[configured_params, {
'yaml_filename': map_yaml_file}],
189 remappings=remappings,
192 package=
'nav2_lifecycle_manager',
193 executable=
'lifecycle_manager',
194 name=
'lifecycle_manager_map_server',
198 {
'autostart': autostart}, {
'node_names': [
'map_server']}],
204 ld = LaunchDescription()
207 ld.add_action(declare_namespace_cmd)
208 ld.add_action(declare_map_yaml_cmd)
209 ld.add_action(declare_graph_file_cmd)
210 ld.add_action(declare_params_file_cmd)
211 ld.add_action(declare_autostart_cmd)
212 ld.add_action(declare_use_composition_cmd)
214 ld.add_action(declare_rviz_config_file_cmd)
215 ld.add_action(declare_use_robot_state_pub_cmd)
216 ld.add_action(declare_use_rviz_cmd)
217 ld.add_action(declare_use_respawn_cmd)
220 ld.add_action(start_robot_state_publisher_cmd)
221 ld.add_action(static_publisher_cmd)
222 ld.add_action(start_map_server)
223 ld.add_action(loopback_sim_cmd)
224 ld.add_action(rviz_cmd)
225 ld.add_action(bringup_cmd)