Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/ros2/ardupilot_sitl/launch/sitl_dds_serial.launch.py
Views: 1800
# Copyright 2023 ArduPilot.org.1#2# This program is free software: you can redistribute it and/or modify3# it under the terms of the GNU General Public License as published by4# the Free Software Foundation, either version 3 of the License, or5# (at your option) any later version.6#7# This program is distributed in the hope that it will be useful,8# but WITHOUT ANY WARRANTY; without even the implied warranty of9# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the10# GNU General Public License for more details.11#12# You should have received a copy of the GNU General Public License13# along with this program. If not, see <https://www.gnu.org/licenses/>.1415"""16Launch ArduPilot SITL, MAVProxy and the microROS DDS agent.1718Run with default arguments:1920ros2 launch ardupilot_sitl sitl_dds_serial.launch.py21"""22from launch import LaunchDescription23from launch.actions import IncludeLaunchDescription24from launch.launch_description_sources import PythonLaunchDescriptionSource25from launch.substitutions import PathJoinSubstitution2627from launch_ros.substitutions import FindPackageShare282930def generate_launch_description() -> LaunchDescription:31"""Generate a launch description to bring up ArduPilot SITL with DDS."""32# Compose launch files.33virtual_ports = IncludeLaunchDescription(34PythonLaunchDescriptionSource(35[36PathJoinSubstitution(37[38FindPackageShare("ardupilot_sitl"),39"launch",40"virtual_ports.launch.py",41]42),43]44)45)46micro_ros_agent = IncludeLaunchDescription(47PythonLaunchDescriptionSource(48[49PathJoinSubstitution(50[51FindPackageShare("ardupilot_sitl"),52"launch",53"micro_ros_agent.launch.py",54]55),56]57)58)59sitl = IncludeLaunchDescription(60PythonLaunchDescriptionSource(61[62PathJoinSubstitution(63[64FindPackageShare("ardupilot_sitl"),65"launch",66"sitl.launch.py",67]68),69]70)71)72mavproxy = IncludeLaunchDescription(73PythonLaunchDescriptionSource(74[75PathJoinSubstitution(76[77FindPackageShare("ardupilot_sitl"),78"launch",79"mavproxy.launch.py",80]81),82]83)84)8586return LaunchDescription(87[88virtual_ports,89micro_ros_agent,90sitl,91mavproxy,92]93)949596