3 <!-- MAVROS posix SITL environment launch script -->
4 <!-- launches Gazebo environment and 2x: MAVROS, PX4 SITL, and spawns vehicle -->
5 <!-- vehicle model and world -->
6 <arg name="est" default="ekf2"/>
7 <arg name="vehicle" default="F550"/>
8 <arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
9 <!-- gazebo configs -->
10 <arg name="gui" default="true"/>
11 <arg name="debug" default="false"/>
12 <arg name="verbose" default="false"/>
13 <arg name="paused" default="false"/>
15 <include file="$(find gazebo_ros)/launch/empty_world.launch">
16 <arg name="gui" value="$(arg gui)"/>
17 <arg name="world_name" value="$(arg world)"/>
18 <arg name="debug" value="$(arg debug)"/>
19 <arg name="verbose" value="$(arg verbose)"/>
20 <arg name="paused" value="$(arg paused)"/>
24 <!-- MAVROS and vehicle configs -->
25 <arg name="ID" value="1"/>
26 <arg name="fcu_url" default="udp://:14541@localhost:14581"/>
27 <!-- PX4 SITL and vehicle spawn -->
28 <include file="$(find px4_simulation_stack)/launch/hexa/single_hexa_spawn.launch">
29 <arg name="x" value="0"/>
30 <arg name="y" value="0"/>
31 <arg name="z" value="0"/>
32 <arg name="R" value="0"/>
33 <arg name="P" value="0"/>
34 <arg name="Y" value="0"/>
35 <arg name="vehicle" value="$(arg vehicle)"/>
36 <arg name="mavlink_udp_port" value="14561"/>
37 <arg name="ID" value="$(arg ID)"/>
40 <include file="$(find mavros)/launch/px4.launch">
41 <arg name="fcu_url" value="$(arg fcu_url)"/>
42 <arg name="gcs_url" value=""/>
43 <arg name="tgt_system" value="$(eval 1 + arg('ID'))"/>
44 <arg name="tgt_component" value="1"/>
49 <!-- MAVROS and vehicle configs -->
50 <arg name="ID" value="2"/>
51 <arg name="fcu_url" default="udp://:14542@localhost:14582"/>
52 <!-- PX4 SITL and vehicle spawn -->
53 <include file="$(find px4_simulation_stack)/launch/hexa/single_hexa_spawn.launch">
54 <arg name="x" value="1"/>
55 <arg name="y" value="0"/>
56 <arg name="z" value="0"/>
57 <arg name="R" value="0"/>
58 <arg name="P" value="0"/>
59 <arg name="Y" value="0"/>
60 <arg name="vehicle" value="$(arg vehicle)"/>
61 <arg name="mavlink_udp_port" value="14562"/>
62 <arg name="ID" value="$(arg ID)"/>
65 <include file="$(find mavros)/launch/px4.launch">
66 <arg name="fcu_url" value="$(arg fcu_url)"/>
67 <arg name="gcs_url" value=""/>
68 <arg name="tgt_system" value="$(eval 1 + arg('ID'))"/>
69 <arg name="tgt_component" value="1"/>
75 <!-- MAVROS and vehicle configs -->
76 <arg name="ID" value="3"/>
77 <arg name="fcu_url" default="udp://:14543@localhost:14583"/>
78 <!-- PX4 SITL and vehicle spawn -->
79 <include file="$(find px4_simulation_stack)/launch/hexa/single_hexa_spawn.launch">
80 <arg name="x" value="0"/>
81 <arg name="y" value="1"/>
82 <arg name="z" value="0"/>
83 <arg name="R" value="0"/>
84 <arg name="P" value="0"/>
85 <arg name="Y" value="0"/>
86 <arg name="vehicle" value="$(arg vehicle)"/>
87 <arg name="mavlink_udp_port" value="14563"/>
88 <arg name="ID" value="$(arg ID)"/>
91 <include file="$(find mavros)/launch/px4.launch">
92 <arg name="fcu_url" value="$(arg fcu_url)"/>
93 <arg name="gcs_url" value=""/>
94 <arg name="tgt_system" value="$(eval 1 + arg('ID'))"/>
95 <arg name="tgt_component" value="1"/>
99 <!-- to add more UAVs (up to 10):
101 Change the name space
102 Set the FCU to default="udp://:14540+id@localhost:14550+id"
103 Set the malink_udp_port to 14560+id) -->