2016-04-20 16:51:58 +02:00
|
|
|
<launch>
|
|
|
|
|
<!-- MAVROS posix SITL environment launch script -->
|
|
|
|
|
|
|
|
|
|
<arg name="headless" default="false"/>
|
|
|
|
|
<arg name="gui" default="true"/>
|
|
|
|
|
<arg name="ns" default="/"/>
|
2016-08-05 21:29:49 +02:00
|
|
|
<arg name="world" default="iris"/>
|
2016-04-20 16:51:58 +02:00
|
|
|
<arg name="build" default="posix_sitl_default"/>
|
2016-05-25 22:28:13 +02:00
|
|
|
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
2016-04-20 16:51:58 +02:00
|
|
|
|
|
|
|
|
<include file="$(find px4)/launch/posix_sitl.launch">
|
|
|
|
|
<arg name="headless" value="$(arg headless)"/>
|
|
|
|
|
<arg name="gui" value="$(arg gui)"/>
|
|
|
|
|
<arg name="ns" value="$(arg ns)"/>
|
2016-08-05 21:29:49 +02:00
|
|
|
<arg name="world" value="$(arg world)"/>
|
2016-04-20 16:51:58 +02:00
|
|
|
<arg name="build" value="$(arg build)"/>
|
|
|
|
|
</include>
|
|
|
|
|
|
|
|
|
|
<include file="$(find px4)/launch/mavros.launch">
|
|
|
|
|
<arg name="ns" value="$(arg ns)"/>
|
2016-04-25 17:04:33 +02:00
|
|
|
<arg name="gcs_url" value=""/> <!-- GCS link is provided by SITL -->
|
2016-05-25 22:28:13 +02:00
|
|
|
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
2016-04-20 16:51:58 +02:00
|
|
|
</include>
|
|
|
|
|
</launch>
|