Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
tb3_simulation_launch.py
1 # Copyright (C) 2023 Open Source Robotics Foundation
2 #
3 # Licensed under the Apache License, Version 2.0 (the "License");
4 # you may not use this file except in compliance with the License.
5 # You may obtain a copy of the License at
6 #
7 # http://www.apache.org/licenses/LICENSE-2.0
8 #
9 # Unless required by applicable law or agreed to in writing, software
10 # distributed under the License is distributed on an "AS IS" BASIS,
11 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 # See the License for the specific language governing permissions and
13 # limitations under the License.
14 
15 """This is all-in-one launch script intended for use by nav2 developers."""
16 
17 import os
18 import tempfile
19 
20 from ament_index_python.packages import get_package_share_directory
21 from launch import LaunchDescription
22 from launch.actions import (DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription,
23  OpaqueFunction, RegisterEventHandler)
24 from launch.conditions import IfCondition
25 from launch.event_handlers import OnShutdown
26 from launch.launch_description_sources import PythonLaunchDescriptionSource
27 from launch.substitutions import LaunchConfiguration, PythonExpression
28 from launch_ros.actions import Node
29 
30 
31 def generate_launch_description() -> LaunchDescription:
32  # Get the launch directory
33  bringup_dir = get_package_share_directory('nav2_bringup')
34  launch_dir = os.path.join(bringup_dir, 'launch')
35  sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
36 
37  # Create the launch configuration variables
38  slam = LaunchConfiguration('slam')
39  namespace = LaunchConfiguration('namespace')
40  map_yaml_file = LaunchConfiguration('map')
41  graph_filepath = LaunchConfiguration('graph')
42  use_sim_time = LaunchConfiguration('use_sim_time')
43  params_file = LaunchConfiguration('params_file')
44  autostart = LaunchConfiguration('autostart')
45  use_composition = LaunchConfiguration('use_composition')
46  use_respawn = LaunchConfiguration('use_respawn')
47 
48  # Launch configuration variables specific to simulation
49  rviz_config_file = LaunchConfiguration('rviz_config_file')
50  use_simulator = LaunchConfiguration('use_simulator')
51  use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
52  use_rviz = LaunchConfiguration('use_rviz')
53  headless = LaunchConfiguration('headless')
54  world = LaunchConfiguration('world')
55  pose = {
56  'x': LaunchConfiguration('x_pose', default='-2.00'),
57  'y': LaunchConfiguration('y_pose', default='-0.50'),
58  'z': LaunchConfiguration('z_pose', default='0.01'),
59  'R': LaunchConfiguration('roll', default='0.00'),
60  'P': LaunchConfiguration('pitch', default='0.00'),
61  'Y': LaunchConfiguration('yaw', default='0.00'),
62  }
63  robot_name = LaunchConfiguration('robot_name')
64  robot_sdf = LaunchConfiguration('robot_sdf')
65 
66  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
67 
68  # Declare the launch arguments
69  declare_namespace_cmd = DeclareLaunchArgument(
70  'namespace', default_value='', description='Top-level namespace'
71  )
72 
73  declare_slam_cmd = DeclareLaunchArgument(
74  'slam', default_value='False', description='Whether run a SLAM'
75  )
76 
77  declare_map_yaml_cmd = DeclareLaunchArgument(
78  'map',
79  default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'),
80  )
81 
82  declare_graph_file_cmd = DeclareLaunchArgument(
83  'graph',
84  default_value=os.path.join(bringup_dir, 'graphs', 'turtlebot3_graph.geojson'),
85  )
86 
87  declare_use_sim_time_cmd = DeclareLaunchArgument(
88  'use_sim_time',
89  default_value='true',
90  description='Use simulation (Gazebo) clock if true',
91  )
92 
93  declare_params_file_cmd = DeclareLaunchArgument(
94  'params_file',
95  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
96  description='Full path to the ROS2 parameters file to use for all launched nodes',
97  )
98 
99  declare_autostart_cmd = DeclareLaunchArgument(
100  'autostart',
101  default_value='true',
102  description='Automatically startup the nav2 stack',
103  )
104 
105  declare_use_composition_cmd = DeclareLaunchArgument(
106  'use_composition',
107  default_value='True',
108  description='Whether to use composed bringup',
109  )
110 
111  declare_use_respawn_cmd = DeclareLaunchArgument(
112  'use_respawn',
113  default_value='False',
114  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
115  )
116 
117  declare_rviz_config_file_cmd = DeclareLaunchArgument(
118  'rviz_config_file',
119  default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
120  description='Full path to the RVIZ config file to use',
121  )
122 
123  declare_use_simulator_cmd = DeclareLaunchArgument(
124  'use_simulator',
125  default_value='True',
126  description='Whether to start the simulator',
127  )
128 
129  declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
130  'use_robot_state_pub',
131  default_value='True',
132  description='Whether to start the robot state publisher',
133  )
134 
135  declare_use_rviz_cmd = DeclareLaunchArgument(
136  'use_rviz', default_value='True', description='Whether to start RVIZ'
137  )
138 
139  declare_simulator_cmd = DeclareLaunchArgument(
140  'headless', default_value='True', description='Whether to execute gzclient)'
141  )
142 
143  declare_world_cmd = DeclareLaunchArgument(
144  'world',
145  default_value=os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro'),
146  description='Full path to world model file to load',
147  )
148 
149  declare_robot_name_cmd = DeclareLaunchArgument(
150  'robot_name', default_value='turtlebot3_waffle', description='name of the robot'
151  )
152 
153  declare_robot_sdf_cmd = DeclareLaunchArgument(
154  'robot_sdf',
155  default_value=os.path.join(sim_dir, 'urdf', 'gz_waffle.sdf.xacro'),
156  description='Full path to robot sdf file to spawn the robot in gazebo',
157  )
158 
159  urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
160  with open(urdf, 'r') as infp:
161  robot_description = infp.read()
162 
163  start_robot_state_publisher_cmd = Node(
164  condition=IfCondition(use_robot_state_pub),
165  package='robot_state_publisher',
166  executable='robot_state_publisher',
167  name='robot_state_publisher',
168  namespace=namespace,
169  output='screen',
170  parameters=[
171  {'use_sim_time': use_sim_time, 'robot_description': robot_description}
172  ],
173  remappings=remappings,
174  )
175 
176  rviz_cmd = IncludeLaunchDescription(
177  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
178  condition=IfCondition(use_rviz),
179  launch_arguments={
180  'namespace': namespace,
181  'use_sim_time': use_sim_time,
182  'rviz_config': rviz_config_file,
183  }.items(),
184  )
185 
186  bringup_cmd = IncludeLaunchDescription(
187  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
188  launch_arguments={
189  'namespace': namespace,
190  'slam': slam,
191  'map': map_yaml_file,
192  'graph': graph_filepath,
193  'use_sim_time': use_sim_time,
194  'params_file': params_file,
195  'autostart': autostart,
196  'use_composition': use_composition,
197  'use_respawn': use_respawn,
198  'use_keepout_zones': 'False',
199  'use_speed_zones': 'False',
200  }.items(),
201  )
202  # The SDF file for the world is a xacro file because we wanted to
203  # conditionally load the SceneBroadcaster plugin based on whether we're
204  # running in headless mode. But currently, the Gazebo command line doesn't
205  # take SDF strings for worlds, so the output of xacro needs to be saved into
206  # a temporary file and passed to Gazebo.
207  world_sdf = tempfile.mktemp(prefix='nav2_', suffix='.sdf')
208  world_sdf_xacro = ExecuteProcess(
209  cmd=['xacro', '-o', world_sdf, ['headless:=', headless], world])
210  gazebo_server = ExecuteProcess(
211  cmd=['gz', 'sim', '-r', '-s', world_sdf],
212  output='screen',
213  condition=IfCondition(use_simulator)
214  )
215 
216  remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
217  on_shutdown=[
218  OpaqueFunction(function=lambda _: os.remove(world_sdf))
219  ]))
220 
221  gazebo_client = IncludeLaunchDescription(
222  PythonLaunchDescriptionSource(
223  os.path.join(get_package_share_directory('ros_gz_sim'),
224  'launch',
225  'gz_sim.launch.py')
226  ),
227  condition=IfCondition(PythonExpression(
228  [use_simulator, ' and not ', headless])),
229  launch_arguments={'gz_args': ['-v4 -g ']}.items(),
230  )
231 
232  gz_robot = IncludeLaunchDescription(
233  PythonLaunchDescriptionSource(
234  os.path.join(sim_dir, 'launch', 'spawn_tb3.launch.py')),
235  launch_arguments={'namespace': namespace,
236  'use_sim_time': use_sim_time,
237  'robot_name': robot_name,
238  'robot_sdf': robot_sdf,
239  'x_pose': pose['x'],
240  'y_pose': pose['y'],
241  'z_pose': pose['z'],
242  'roll': pose['R'],
243  'pitch': pose['P'],
244  'yaw': pose['Y']}.items())
245 
246  # Create the launch description and populate
247  ld = LaunchDescription()
248 
249  # Declare the launch options
250  ld.add_action(declare_namespace_cmd)
251  ld.add_action(declare_slam_cmd)
252  ld.add_action(declare_map_yaml_cmd)
253  ld.add_action(declare_graph_file_cmd)
254  ld.add_action(declare_use_sim_time_cmd)
255  ld.add_action(declare_params_file_cmd)
256  ld.add_action(declare_autostart_cmd)
257  ld.add_action(declare_use_composition_cmd)
258 
259  ld.add_action(declare_rviz_config_file_cmd)
260  ld.add_action(declare_use_simulator_cmd)
261  ld.add_action(declare_use_robot_state_pub_cmd)
262  ld.add_action(declare_use_rviz_cmd)
263  ld.add_action(declare_simulator_cmd)
264  ld.add_action(declare_world_cmd)
265  ld.add_action(declare_robot_name_cmd)
266  ld.add_action(declare_robot_sdf_cmd)
267  ld.add_action(declare_use_respawn_cmd)
268 
269  ld.add_action(world_sdf_xacro)
270  ld.add_action(remove_temp_sdf_file)
271  ld.add_action(gz_robot)
272  ld.add_action(gazebo_server)
273  ld.add_action(gazebo_client)
274 
275  # Add the actions to launch all of the navigation nodes
276  ld.add_action(start_robot_state_publisher_cmd)
277  ld.add_action(rviz_cmd)
278  ld.add_action(bringup_cmd)
279 
280  return ld