2016-04-20 11:51:58 -03:00
|
|
|
<launch>
|
2016-08-25 16:47:45 -03:00
|
|
|
|
2016-04-20 11:51:58 -03:00
|
|
|
<!-- MAVROS posix SITL environment launch script -->
|
2016-08-25 16:47:45 -03:00
|
|
|
<arg name="x" default="0"/>
|
|
|
|
<arg name="y" default="0"/>
|
|
|
|
<arg name="z" default="0"/>
|
|
|
|
<arg name="R" default="0"/>
|
|
|
|
<arg name="P" default="0"/>
|
|
|
|
<arg name="Y" default="0"/>
|
|
|
|
|
|
|
|
|
|
|
|
<arg name="est" default="lpe"/>
|
|
|
|
<arg name="vehicle" default="iris"/>
|
|
|
|
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
|
|
|
|
<arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>
|
|
|
|
|
|
|
|
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)"/>
|
2016-04-20 11:51:58 -03:00
|
|
|
|
|
|
|
<arg name="headless" default="false"/>
|
|
|
|
<arg name="gui" default="true"/>
|
|
|
|
<arg name="ns" default="/"/>
|
2016-05-25 17:28:13 -03:00
|
|
|
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
2016-04-20 11:51:58 -03:00
|
|
|
|
2016-08-25 16:47:45 -03:00
|
|
|
<arg name="debug" default="false"/>
|
|
|
|
<arg name="verbose" default="false"/>
|
|
|
|
<arg name="paused" default="false"/>
|
|
|
|
|
2016-10-01 10:02:12 -03:00
|
|
|
<arg name="pluginlists_yaml" default="$(find mavros)/launch/px4_pluginlists.yaml" />
|
|
|
|
<arg name="config_yaml" default="$(find mavros)/launch/px4_config.yaml" />
|
|
|
|
|
2016-04-20 11:51:58 -03:00
|
|
|
<include file="$(find px4)/launch/posix_sitl.launch">
|
2016-08-25 16:47:45 -03:00
|
|
|
<arg name="x" value="$(arg x)"/>
|
|
|
|
<arg name="y" value="$(arg y)"/>
|
|
|
|
<arg name="z" value="$(arg z)"/>
|
|
|
|
<arg name="R" value="$(arg R)"/>
|
|
|
|
<arg name="P" value="$(arg P)"/>
|
|
|
|
<arg name="Y" value="$(arg Y)"/>
|
|
|
|
<arg name="world" value="$(arg world)"/>
|
|
|
|
<arg name="vehicle" value="$(arg vehicle)"/>
|
|
|
|
<arg name="sdf" value="$(arg sdf)"/>
|
|
|
|
<arg name="rcS" value="$(arg rcS)"/>
|
2016-04-20 11:51:58 -03:00
|
|
|
<arg name="headless" value="$(arg headless)"/>
|
|
|
|
<arg name="gui" value="$(arg gui)"/>
|
|
|
|
<arg name="ns" value="$(arg ns)"/>
|
2016-08-25 16:47:45 -03:00
|
|
|
<arg name="debug" value="$(arg debug)"/>
|
|
|
|
<arg name="verbose" value="$(arg verbose)"/>
|
|
|
|
<arg name="paused" value="$(arg paused)"/>
|
2016-04-20 11:51:58 -03:00
|
|
|
</include>
|
|
|
|
|
|
|
|
<include file="$(find px4)/launch/mavros.launch">
|
|
|
|
<arg name="ns" value="$(arg ns)"/>
|
2016-04-25 12:04:33 -03:00
|
|
|
<arg name="gcs_url" value=""/> <!-- GCS link is provided by SITL -->
|
2016-05-25 17:28:13 -03:00
|
|
|
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
2016-10-01 10:02:12 -03:00
|
|
|
<arg name="pluginlists_yaml" value="$(arg pluginlists_yaml)" />
|
|
|
|
<arg name="config_yaml" value="$(arg config_yaml)" />
|
2016-04-20 11:51:58 -03:00
|
|
|
</include>
|
|
|
|
</launch>
|
2016-08-25 16:47:45 -03:00
|
|
|
|
|
|
|
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
|