4 <arg name="x" default="0"/>
5 <arg name="y" default="0"/>
6 <arg name="z" default="0"/>
7 <arg name="R" default="0"/>
8 <arg name="P" default="0"/>
9 <arg name="Y" default="0"/>
11 <!-- vehcile model and config -->
12 <arg name="est" default="ekf2"/>
13 <arg name="vehicle" default="F550"/>
14 <arg name="ID" default="1"/>
15 <env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
16 <env name="PX4_ESTIMATOR" value="$(arg est)" />
17 <arg name="mavlink_udp_port" default="14560"/>
19 <!-- generate urdf vehicle model -->
20 <arg name="xacro_file" default="$(find px4_simulation_stack)/Tools/sitl_gazebo/models/$(arg vehicle)/xacro/$(arg vehicle).xacro"/>
21 <arg name="cmd" default="$(find xacro)/xacro $(arg xacro_file) mavlink_udp_port:=$(arg mavlink_udp_port) --inorder"/>
23 <include file="$(find px4)/launch/single_vehicle_spawn.launch">
24 <arg name="x" value="$(arg x)" />
25 <arg name="y" value="$(arg y)" />
26 <arg name="z" value="$(arg z)" />
27 <arg name="R" value="$(arg R)" />
28 <arg name="P" value="$(arg P)" />
29 <arg name="Y" value="$(arg Y)" />
31 <arg name="est" value="$(arg est)"/>
32 <arg name="vehicle" value="$(arg vehicle)"/>
33 <arg name="ID" value="$(arg ID)"/>
34 <arg name="mavlink_udp_port" value="$(arg mavlink_udp_port)"/>
35 <arg name="cmd" value="$(arg cmd)"/>