2018-02-09 14:40:38 -04:00
|
|
|
<?xml version="1.0"?>
|
2016-04-20 11:51:58 -03:00
|
|
|
<launch>
|
|
|
|
<!-- MAVROS posix SITL environment launch script -->
|
2018-02-09 14:40:38 -04:00
|
|
|
<!-- launches MAVROS, PX4 SITL, Gazebo environment, and spawns vehicle -->
|
|
|
|
<!-- vehicle pose -->
|
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"/>
|
2018-02-09 14:40:38 -04:00
|
|
|
<!-- vehicle model and world -->
|
2018-01-01 00:21:44 -04:00
|
|
|
<arg name="est" default="ekf2"/>
|
2016-08-25 16:47:45 -03:00
|
|
|
<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)"/>
|
2018-02-09 14:40:38 -04:00
|
|
|
<!-- gazebo configs -->
|
2016-04-20 11:51:58 -03:00
|
|
|
<arg name="gui" default="true"/>
|
2016-08-25 16:47:45 -03:00
|
|
|
<arg name="debug" default="false"/>
|
|
|
|
<arg name="verbose" default="false"/>
|
|
|
|
<arg name="paused" default="false"/>
|
2018-02-06 16:11:09 -04:00
|
|
|
<arg name="respawn_gazebo" default="false"/>
|
2018-03-31 09:21:52 -03:00
|
|
|
<!-- MAVROS configs -->
|
2018-02-09 14:40:38 -04:00
|
|
|
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
2018-03-31 09:21:52 -03:00
|
|
|
<arg name="respawn_mavros" default="false"/>
|
2018-06-14 13:37:47 -03:00
|
|
|
<!-- PX4 configs -->
|
|
|
|
<arg name="interactive" default="true"/>
|
2018-02-09 14:40:38 -04:00
|
|
|
<!-- PX4 SITL and Gazebo -->
|
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="gui" value="$(arg gui)"/>
|
2018-06-14 13:37:47 -03:00
|
|
|
<arg name="interactive" value="$(arg interactive)"/>
|
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)"/>
|
2018-02-06 16:11:09 -04:00
|
|
|
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
|
2016-04-20 11:51:58 -03:00
|
|
|
</include>
|
2018-02-09 14:40:38 -04:00
|
|
|
<!-- MAVROS -->
|
|
|
|
<include file="$(find mavros)/launch/px4.launch">
|
|
|
|
<!-- GCS link is provided by SITL -->
|
|
|
|
<arg name="gcs_url" value=""/>
|
2016-05-25 17:28:13 -03:00
|
|
|
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
2018-03-31 09:21:52 -03:00
|
|
|
<arg name="respawn_mavros" value="$(arg respawn_mavros)"/>
|
2016-04-20 11:51:58 -03:00
|
|
|
</include>
|
|
|
|
</launch>
|