forked from Archive/PX4-Autopilot
104 lines
4.1 KiB
XML
104 lines
4.1 KiB
XML
<?xml version="1.0"?>
|
|
<launch>
|
|
<!-- MAVROS posix SITL environment launch script -->
|
|
<!-- launches Gazebo environment and 2x: MAVROS, PX4 SITL, and spawns vehicle -->
|
|
<!-- vehicle model and world -->
|
|
<arg name="est" default="ekf2"/>
|
|
<arg name="vehicle" default="iris"/>
|
|
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
|
|
<!-- gazebo configs -->
|
|
<arg name="gui" default="true"/>
|
|
<arg name="debug" default="false"/>
|
|
<arg name="verbose" default="false"/>
|
|
<arg name="paused" default="false"/>
|
|
<!-- Gazebo sim -->
|
|
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
|
<arg name="gui" value="$(arg gui)"/>
|
|
<arg name="world_name" value="$(arg world)"/>
|
|
<arg name="debug" value="$(arg debug)"/>
|
|
<arg name="verbose" value="$(arg verbose)"/>
|
|
<arg name="paused" value="$(arg paused)"/>
|
|
</include>
|
|
<!-- UAV1 -->
|
|
<group ns="uav1">
|
|
<!-- MAVROS and vehicle configs -->
|
|
<arg name="ID" value="1"/>
|
|
<arg name="fcu_url" default="udp://:14541@localhost:14581"/>
|
|
<!-- PX4 SITL and vehicle spawn -->
|
|
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
|
|
<arg name="x" value="0"/>
|
|
<arg name="y" value="0"/>
|
|
<arg name="z" value="0"/>
|
|
<arg name="R" value="0"/>
|
|
<arg name="P" value="0"/>
|
|
<arg name="Y" value="0"/>
|
|
<arg name="vehicle" value="$(arg vehicle)"/>
|
|
<arg name="mavlink_udp_port" value="14561"/>
|
|
<arg name="ID" value="$(arg ID)"/>
|
|
</include>
|
|
<!-- MAVROS -->
|
|
<include file="$(find mavros)/launch/px4.launch">
|
|
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
|
<arg name="gcs_url" value=""/>
|
|
<arg name="tgt_system" value="$(eval 1 + arg('ID'))"/>
|
|
<arg name="tgt_component" value="1"/>
|
|
</include>
|
|
</group>
|
|
<!-- UAV2 -->
|
|
<group ns="uav2">
|
|
<!-- MAVROS and vehicle configs -->
|
|
<arg name="ID" value="2"/>
|
|
<arg name="fcu_url" default="udp://:14542@localhost:14582"/>
|
|
<!-- PX4 SITL and vehicle spawn -->
|
|
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
|
|
<arg name="x" value="1"/>
|
|
<arg name="y" value="0"/>
|
|
<arg name="z" value="0"/>
|
|
<arg name="R" value="0"/>
|
|
<arg name="P" value="0"/>
|
|
<arg name="Y" value="0"/>
|
|
<arg name="vehicle" value="$(arg vehicle)"/>
|
|
<arg name="mavlink_udp_port" value="14562"/>
|
|
<arg name="ID" value="$(arg ID)"/>
|
|
</include>
|
|
<!-- MAVROS -->
|
|
<include file="$(find mavros)/launch/px4.launch">
|
|
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
|
<arg name="gcs_url" value=""/>
|
|
<arg name="tgt_system" value="$(eval 1 + arg('ID'))"/>
|
|
<arg name="tgt_component" value="1"/>
|
|
</include>
|
|
</group>
|
|
|
|
<!-- UAV3 -->
|
|
<group ns="uav3">
|
|
<!-- MAVROS and vehicle configs -->
|
|
<arg name="ID" value="3"/>
|
|
<arg name="fcu_url" default="udp://:14543@localhost:14583"/>
|
|
<!-- PX4 SITL and vehicle spawn -->
|
|
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
|
|
<arg name="x" value="0"/>
|
|
<arg name="y" value="1"/>
|
|
<arg name="z" value="0"/>
|
|
<arg name="R" value="0"/>
|
|
<arg name="P" value="0"/>
|
|
<arg name="Y" value="0"/>
|
|
<arg name="vehicle" value="$(arg vehicle)"/>
|
|
<arg name="mavlink_udp_port" value="14563"/>
|
|
<arg name="ID" value="$(arg ID)"/>
|
|
</include>
|
|
<!-- MAVROS -->
|
|
<include file="$(find mavros)/launch/px4.launch">
|
|
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
|
<arg name="gcs_url" value=""/>
|
|
<arg name="tgt_system" value="$(eval 1 + arg('ID'))"/>
|
|
<arg name="tgt_component" value="1"/>
|
|
</include>
|
|
</group>
|
|
</launch>
|
|
<!-- to add more UAVs (up to 10):
|
|
Increase the id
|
|
Change the name space
|
|
Set the FCU to default="udp://:14540+id@localhost:14550+id"
|
|
Set the malink_udp_port to 14560+id) -->
|