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.
20 lines
988 B
20 lines
988 B
<?xml version="1.0"?> |
|
<launch> |
|
<!-- Posix SITL MAVROS integration tests --> |
|
<!-- Test offboard local posistion and attitude control with optical flow iris --> |
|
<arg name="est" default="ekf2"/> |
|
<arg name="gui" default="false"/> |
|
<arg name="interactive" default="false"/> |
|
<!-- MAVROS, PX4 SITL, Gazebo --> |
|
<include file="$(find px4)/launch/mavros_posix_sitl.launch"> |
|
<arg name="est" value="$(arg est)"/> |
|
<arg name="gui" value="$(arg gui)"/> |
|
<arg name="interactive" value="$(arg interactive)"/> |
|
<arg name="vehicle" value="iris_opt_flow"/> |
|
<arg name="respawn_gazebo" value="true"/> |
|
<arg name="respawn_mavros" value="true"/> |
|
</include> |
|
<!-- ROStest --> |
|
<test test-name="mavros_flow_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" time-limit="300.0"/> |
|
<test test-name="mavros_flow_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" time-limit="300.0"/> |
|
</launch>
|
|
|