You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 
 
 
 
 

22 lines
1.3 KiB

<?xml version="1.0"?>
<launch>
<!-- Posix SITL MAVROS integration tests -->
<!-- Test all missions with standard VTOL -->
<arg name="gui" default="false"/>
<arg name="est" default="ekf2"/>
<arg name="respawn_gazebo" default="true"/>
<!-- MAVROS, PX4 SITL, Gazebo -->
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
<arg name="gui" value="$(arg gui)"/>
<arg name="vehicle" value="standard_vtol"/>
<arg name="est" value="$(arg est)"/>
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
</include>
<!-- ROStest -->
<test test-name="multicopter_box" pkg="px4" type="mission_test.py" time-limit="120.0" args="multirotor_box.plan"/>
<test test-name="mission_test_new_1" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_new_1.plan"/>
<test test-name="mission_test_new_2" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_new_2.plan"/>
<test test-name="mission_test_old_1" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_1.plan"/>
<test test-name="mission_test_old_2" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_2.plan"/>
<test test-name="mission_test_old_3" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_3.plan"/>
</launch>