forked from Archive/PX4-Autopilot
ROS launch: cleanup
* remove non-functional gazebo headless arg * remove unused namespace args * simplify mavros launch, use mavros's px4.launch instead * fix single_vehicle_spawn spelling * formatting with xmllint: remove empty lines, set intent to 4 spaces, add xml tag for editors, add comments to break up spections * remove old and deprecated launch files
This commit is contained in:
parent
a637063965
commit
b1f08a9640
|
@ -1,22 +0,0 @@
|
|||
<launch>
|
||||
<arg name="ns"/>
|
||||
<arg name="mavlink_fcu_url" default="udp://localhost:14565@localhost:14560"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter_x.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="mavlink_fcu_url" value="$(arg mavlink_fcu_url)" />
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<param name="MPP_XY_P" type="double" value="1.0" />
|
||||
<param name="MPP_XY_FF" type="double" value="0.1" />
|
||||
<param name="MPP_XY_VEL_P" type="double" value="0.01" />
|
||||
<param name="MPP_XY_VEL_I" type="double" value="0.0" />
|
||||
<param name="MPP_XY_VEL_D" type="double" value="0.01" />
|
||||
<param name="MPP_XY_VEL_MAX" type="double" value="2.0" />
|
||||
<param name="MPP_Z_VEL_P" type="double" value="0.3" />
|
||||
<param name="MPP_Z_P" type="double" value="2" />
|
||||
<param name="vehicle_model" type="string" value="ardrone" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,8 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<group ns="px4_example">
|
||||
<node pkg="px4" name="subscriber" type="subscriber"/>
|
||||
<node pkg="px4" name="publisher" type="publisher"/>
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,21 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/ardrone_empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/ardrone.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -1,14 +0,0 @@
|
|||
<launch>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
|
||||
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<group ns="$(arg ns)">
|
||||
<node pkg="px4" name="demo_offboard_attitude_setpoints" type="demo_offboard_attitude_setpoints"/>
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,14 +0,0 @@
|
|||
<launch>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
|
||||
<include file="$(find px4)/launch/gazebo_ardrone_empty_world.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/mavros_sitl.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
<group ns="$(arg ns)">
|
||||
<node pkg="px4" name="demo_offboard_position_setpoints" type="demo_offboard_position_setpoints"/>
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,21 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="ardrone"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/ardrone_house_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/ardrone.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -1,21 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/iris_empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/iris.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -1,21 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/iris_house_world_with_joy.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/iris.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -1,23 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
<arg name="mavlink_bridge_url" default="udp://localhost:14553@localhost:14560" />
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/iris_empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find mavros)/launch/mavlink_bridge.launch">
|
||||
<arg name="mavlink_bridge_url" value="$(arg mavlink_bridge_url)" />
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -1,21 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find rotors_gazebo)/launch/iris_outdoor_world_with_joy.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
</include>
|
||||
<include file="$(find px4)/launch/iris.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -1,59 +0,0 @@
|
|||
<launch>
|
||||
|
||||
<!--
|
||||
MAVROS posix SITL environment launch script modified for hippocam,pus from mavros_posix_sitl.
|
||||
The HippoCampus is an autonomous underwater vehicle (AUV) designed by the Technical University Hamburg-Harburg.
|
||||
https://www.tuhh.de/mum/forschung/forschungsgebiete-und-projekte/flow-field-estimation-with-a-swarm-of-auvs.html
|
||||
-->
|
||||
|
||||
<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="ekf2"/>
|
||||
<arg name="vehicle" default="hippocampus"/>
|
||||
<arg name="world" default="$(find px4)/Tools/sitl_gazebo/worlds/hippocampus.world"/>
|
||||
<arg name="sdf" default="$(find px4)/Tools/sitl_gazebo/models/$(arg vehicle)/$(arg vehicle).sdf"/>
|
||||
|
||||
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)"/>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="ns" default="/"/>
|
||||
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
||||
|
||||
<arg name="debug" default="false"/>
|
||||
<arg name="verbose" default="false"/>
|
||||
<arg name="paused" default="false"/>
|
||||
|
||||
<include file="$(find px4)/launch/posix_sitl.launch">
|
||||
<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)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="verbose" value="$(arg verbose)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
</include>
|
||||
|
||||
<include file="$(find px4)/launch/mavros.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="gcs_url" value=""/> <!-- GCS link is provided by SITL -->
|
||||
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
||||
</include>
|
||||
</launch>
|
||||
|
||||
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
|
|
@ -1,23 +0,0 @@
|
|||
<launch>
|
||||
<arg name="ns"/>
|
||||
<arg name="mavlink_fcu_url" default="udp://localhost:14565@localhost:14560"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter_w.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="mavlink_fcu_url" value="$(arg mavlink_fcu_url)" />
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<param name="mixer" type="string" value="i" />
|
||||
<param name="MPP_XY_P" type="double" value="1.0" />
|
||||
<param name="MPP_XY_FF" type="double" value="0.0" />
|
||||
<param name="MPP_XY_VEL_P" type="double" value="0.01" />
|
||||
<param name="MPP_XY_VEL_I" type="double" value="0.0" />
|
||||
<param name="MPP_XY_VEL_D" type="double" value="0.01" />
|
||||
<param name="MPP_XY_VEL_MAX" type="double" value="2.0" />
|
||||
<param name="MPP_Z_VEL_P" type="double" value="0.3" />
|
||||
<param name="MPP_Z_P" type="double" value="2" />
|
||||
<param name="vehicle_model" type="string" value="iris" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,25 +0,0 @@
|
|||
<launch>
|
||||
<!-- MAVROS launch script PX4 (default) -->
|
||||
|
||||
<arg name="ns" default="/" />
|
||||
<arg name="fcu_url" default="" />
|
||||
<arg name="gcs_url" default="udp://:14550@:14555" />
|
||||
<arg name="tgt_system" default="1" />
|
||||
<arg name="tgt_component" default="1" />
|
||||
<arg name="pluginlists_yaml" default="$(find mavros)/launch/px4_pluginlists.yaml" />
|
||||
<arg name="config_yaml" default="$(find mavros)/launch/px4_config.yaml" />
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="pluginlists_yaml" value="$(arg pluginlists_yaml)" />
|
||||
<arg name="config_yaml" value="$(arg config_yaml)" />
|
||||
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
<arg name="gcs_url" value="$(arg gcs_url)" />
|
||||
<arg name="tgt_system" value="$(arg tgt_system)" />
|
||||
<arg name="tgt_component" value="$(arg tgt_component)" />
|
||||
</include>
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
<!-- vim: set ft=xml et fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
|
|
@ -1,34 +1,29 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- MAVROS posix SITL environment launch script -->
|
||||
<!-- launches MAVROS, PX4 SITL, Gazebo environment, and spawns vehicle -->
|
||||
<!-- vehicle pose -->
|
||||
<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"/>
|
||||
|
||||
|
||||
<!-- vehicle model and world -->
|
||||
<arg name="est" default="ekf2"/>
|
||||
<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)"/>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<!-- gazebo configs -->
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="ns" default="/"/>
|
||||
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
||||
|
||||
<arg name="debug" default="false"/>
|
||||
<arg name="verbose" default="false"/>
|
||||
<arg name="paused" default="false"/>
|
||||
<arg name="respawn_gazebo" default="false"/>
|
||||
|
||||
<arg name="pluginlists_yaml" default="$(find mavros)/launch/px4_pluginlists.yaml" />
|
||||
<arg name="config_yaml" default="$(find mavros)/launch/px4_config.yaml" />
|
||||
|
||||
<!-- MAVROS connection -->
|
||||
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
||||
<!-- PX4 SITL and Gazebo -->
|
||||
<include file="$(find px4)/launch/posix_sitl.launch">
|
||||
<arg name="x" value="$(arg x)"/>
|
||||
<arg name="y" value="$(arg y)"/>
|
||||
|
@ -40,22 +35,16 @@
|
|||
<arg name="vehicle" value="$(arg vehicle)"/>
|
||||
<arg name="sdf" value="$(arg sdf)"/>
|
||||
<arg name="rcS" value="$(arg rcS)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="verbose" value="$(arg verbose)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
|
||||
</include>
|
||||
|
||||
<include file="$(find px4)/launch/mavros.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="gcs_url" value=""/> <!-- GCS link is provided by SITL -->
|
||||
<!-- MAVROS -->
|
||||
<include file="$(find mavros)/launch/px4.launch">
|
||||
<!-- GCS link is provided by SITL -->
|
||||
<arg name="gcs_url" value=""/>
|
||||
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
||||
<arg name="pluginlists_yaml" value="$(arg pluginlists_yaml)" />
|
||||
<arg name="config_yaml" value="$(arg config_yaml)" />
|
||||
</include>
|
||||
</launch>
|
||||
|
||||
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
|
||||
|
|
|
@ -1,21 +0,0 @@
|
|||
<launch>
|
||||
<!-- MAVROS launch script for deprecated multiplatform SITL -->
|
||||
|
||||
<arg name="ns" default="/" />
|
||||
<arg name="fcu_url" default="udp://localhost:14560@localhost:14565" />
|
||||
<arg name="gcs_url" default="" />
|
||||
<arg name="tgt_system" default="1" />
|
||||
<arg name="tgt_component" default="50" />
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml" />
|
||||
<arg name="config_yaml" value="$(find mavros)/launch/px4_config.yaml" />
|
||||
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
<arg name="gcs_url" value="$(arg gcs_url)" />
|
||||
<arg name="tgt_system" value="$(arg tgt_system)" />
|
||||
<arg name="tgt_component" value="$(arg tgt_component)" />
|
||||
</include>
|
||||
</group>
|
||||
</launch>
|
|
@ -1,55 +0,0 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<arg name="headless" default="false"/>
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="enable_logging" default="false"/>
|
||||
<arg name="enable_ground_truth" default="true"/>
|
||||
<arg name="debug" default="false"/>
|
||||
<arg name="ns" default="iris"/>
|
||||
<arg name="log_file" default="$(arg ns)"/>
|
||||
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="world_name" value="$(find rotors_gazebo)/worlds/basic.world"/>
|
||||
<arg name="debug" value="$(arg debug)" />
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
</include>
|
||||
|
||||
<group ns="iris">
|
||||
<include file="$(find rotors_gazebo)/launch/spawn_iris.launch">
|
||||
<arg name="model" value="$(find rotors_description)/urdf/iris_gesture_sensors.gazebo" />
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
<arg name="x" value="1"/>
|
||||
<arg name="y" value="0"/>
|
||||
</include>
|
||||
<arg name="fcu_url" default="udp://localhost:14560@localhost:14565" />
|
||||
<include file="$(find mavros)/launch/px4.launch">
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
</include>
|
||||
</group>
|
||||
<include file="$(find px4)/launch/iris.launch">
|
||||
<arg name="ns" value="iris"/>
|
||||
</include>
|
||||
|
||||
<group ns="ardrone">
|
||||
<include file="$(find rotors_gazebo)/launch/spawn_ardrone.launch">
|
||||
<arg name="model" value="$(find rotors_description)/urdf/ardrone_base.xacro" />
|
||||
<arg name="enable_logging" value="$(arg enable_logging)" />
|
||||
<arg name="enable_ground_truth" value="$(arg enable_ground_truth)" />
|
||||
<arg name="log_file" value="$(arg log_file)"/>
|
||||
<arg name="x" value="-1"/>
|
||||
<arg name="y" value="0"/>
|
||||
</include>
|
||||
<arg name="fcu_url" default="udp://localhost:14570@localhost:14575" />
|
||||
<include file="$(find mavros)/launch/px4.launch">
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
</include>
|
||||
</group>
|
||||
<include file="$(find px4)/launch/ardrone.launch">
|
||||
<arg name="ns" value="ardrone"/>
|
||||
<arg name="mavlink_fcu_url" value="udp://localhost:14575@localhost:14570"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
|
@ -1,42 +1,31 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- MAVROS posix SITL environment launch script -->
|
||||
|
||||
<arg name="debug" default="false"/>
|
||||
<arg name="verbose" default="false"/>
|
||||
<arg name="paused" default="false"/>
|
||||
|
||||
<!-- launches Gazebo environment and 2x: MAVROS, PX4 SITL, and spawns vehicle -->
|
||||
<!-- vehicle model and world -->
|
||||
<arg name="est" default="ekf2"/>
|
||||
<arg name="vehicle" default="iris"/>
|
||||
<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/empty.world"/>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<!-- gazebo configs -->
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="ns" default="/"/>
|
||||
|
||||
<arg name="pluginlists_yaml" default="$(find mavros)/launch/px4_pluginlists.yaml" />
|
||||
<arg name="config_yaml" default="$(find mavros)/launch/px4_config.yaml" />
|
||||
|
||||
<!-- Load world -->
|
||||
<arg name="debug" default="false"/>
|
||||
<arg name="verbose" default="false"/>
|
||||
<arg name="paused" default="false"/>
|
||||
<!-- Gazebo sim -->
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="world_name" value="$(arg world)" />
|
||||
<arg name="debug" value="$(arg debug)" />
|
||||
<arg name="verbose" value="$(arg verbose)" />
|
||||
<arg name="paused" value="$(arg paused)" />
|
||||
<arg name="world_name" value="$(arg world)"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="verbose" value="$(arg verbose)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
</include>
|
||||
|
||||
<!-- UAV1 iris_1-->
|
||||
<!-- UAV1 -->
|
||||
<group ns="uav1">
|
||||
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
||||
<arg name="gcs_url" value=""/>
|
||||
<arg name="tgt_system" value="1"/>
|
||||
<arg name="tgt_component" value="1"/>
|
||||
<arg name="rcS1" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_1"/>
|
||||
<!-- MAVROS and vehicle configs -->
|
||||
<arg name="ID" value="1"/>
|
||||
|
||||
<include file="$(find px4)/launch/single_vehcile_spawn.launch">
|
||||
<arg name="fcu_url" default="udp://:14540@localhost:14557"/>
|
||||
<!-- PX4 SITL and vehicle spawn -->
|
||||
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
|
||||
<arg name="x" value="0"/>
|
||||
<arg name="y" value="0"/>
|
||||
<arg name="z" value="0"/>
|
||||
|
@ -44,32 +33,25 @@
|
|||
<arg name="P" value="0"/>
|
||||
<arg name="Y" value="0"/>
|
||||
<arg name="vehicle" value="$(arg vehicle)"/>
|
||||
<arg name="rcS" value="$(arg rcS1)"/>
|
||||
<arg name="rcS" value="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
|
||||
<arg name="mavlink_udp_port" value="14560"/>
|
||||
<arg name="ID" value="$(arg ID)"/>
|
||||
</include>
|
||||
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="pluginlists_yaml" value="$(arg pluginlists_yaml)" />
|
||||
<arg name="config_yaml" value="$(arg config_yaml)" />
|
||||
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
<arg name="gcs_url" value="$(arg gcs_url)" />
|
||||
<arg name="tgt_system" value="$(arg tgt_system)" />
|
||||
<arg name="tgt_component" value="$(arg tgt_component)" />
|
||||
<!-- MAVROS -->
|
||||
<include file="$(find mavros)/launch/px4.launch">
|
||||
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
||||
<arg name="gcs_url" value=""/>
|
||||
<arg name="tgt_system" value="$(arg ID)"/>
|
||||
<arg name="tgt_component" value="1"/>
|
||||
</include>
|
||||
</group>
|
||||
|
||||
<!-- UAV2 iris_2 -->
|
||||
<!-- UAV2 -->
|
||||
<group ns="uav2">
|
||||
<arg name="fcu_url" default="udp://:14541@localhost:14559"/>
|
||||
<arg name="gcs_url" value=""/>
|
||||
<arg name="tgt_system" value="2"/>
|
||||
<arg name="tgt_component" value="1"/>
|
||||
<arg name="rcS2" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_2"/>
|
||||
<!-- MAVROS and vehicle configs -->
|
||||
<arg name="ID" value="2"/>
|
||||
|
||||
<include file="$(find px4)/launch/single_vehcile_spawn.launch">
|
||||
<arg name="fcu_url" default="udp://:14541@localhost:14559"/>
|
||||
<!-- PX4 SITL and vehicle spawn -->
|
||||
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
|
||||
<arg name="x" value="1"/>
|
||||
<arg name="y" value="0"/>
|
||||
<arg name="z" value="0"/>
|
||||
|
@ -77,21 +59,16 @@
|
|||
<arg name="P" value="0"/>
|
||||
<arg name="Y" value="0"/>
|
||||
<arg name="vehicle" value="$(arg vehicle)"/>
|
||||
<arg name="rcS" value="$(arg rcS2)"/>
|
||||
<arg name="rcS" value="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
|
||||
<arg name="mavlink_udp_port" value="14562"/>
|
||||
<arg name="ID" value="$(arg ID)"/>
|
||||
</include>
|
||||
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="pluginlists_yaml" value="$(arg pluginlists_yaml)" />
|
||||
<arg name="config_yaml" value="$(arg config_yaml)" />
|
||||
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
<arg name="gcs_url" value="$(arg gcs_url)" />
|
||||
<arg name="tgt_system" value="$(arg tgt_system)" />
|
||||
<arg name="tgt_component" value="$(arg tgt_component)" />
|
||||
<!-- MAVROS -->
|
||||
<include file="$(find mavros)/launch/px4.launch">
|
||||
<arg name="fcu_url" value="$(arg fcu_url)"/>
|
||||
<arg name="gcs_url" value=""/>
|
||||
<arg name="tgt_system" value="$(arg ID)"/>
|
||||
<arg name="tgt_component" value="1"/>
|
||||
</include>
|
||||
</group>
|
||||
|
||||
</launch>
|
||||
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
|
||||
|
|
|
@ -1,20 +0,0 @@
|
|||
<launch>
|
||||
<arg name="ns"/>
|
||||
<arg name="mavlink_fcu_url"/>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<node pkg="joy" name="joy_node" type="joy_node"/>
|
||||
<node pkg="px4" name="manual_input" type="manual_input"/>
|
||||
<node pkg="px4" name="commander" type="commander"/>
|
||||
<node pkg="px4" name="mc_mixer" type="mc_mixer"/>
|
||||
<node pkg="px4" name="attitude_estimator" type="attitude_estimator"/>
|
||||
<node pkg="px4" name="position_estimator" type="position_estimator"/>
|
||||
<node pkg="px4" name="mc_att_control" type="mc_att_control"/>
|
||||
<node pkg="px4" name="mc_pos_control" type="mc_pos_control"/>
|
||||
<node pkg="px4" name="mavlink" type="mavlink">
|
||||
<param name="mavlink_fcu_url" value="$(arg mavlink_fcu_url)" type="str"/>
|
||||
</node>
|
||||
<!-- <node pkg="rosbag" type="record" name="record" output="screen" args="-a -O px4_multicopter"/> -->
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,14 +0,0 @@
|
|||
<launch>
|
||||
<arg name="ns"/>
|
||||
<arg name="mavlink_fcu_url"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="mavlink_fcu_url" value="$(arg mavlink_fcu_url)" />
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<param name="mixer" type="string" value="w" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,14 +0,0 @@
|
|||
<launch>
|
||||
<arg name="ns"/>
|
||||
<arg name="mavlink_fcu_url"/>
|
||||
|
||||
<include file="$(find px4)/launch/multicopter.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="mavlink_fcu_url" value="$(arg mavlink_fcu_url)" />
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<param name="mixer" type="string" value="x" />
|
||||
</group>
|
||||
|
||||
</launch>
|
|
@ -1,45 +1,37 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- Posix SITL environment launch script -->
|
||||
<!-- launches PX4 SITL, Gazebo environment, and spawns vehicle -->
|
||||
<!-- vehicle pose -->
|
||||
<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"/>
|
||||
<!-- vehicle model and world -->
|
||||
<arg name="est" default="ekf2"/>
|
||||
<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)"/>
|
||||
|
||||
<arg name="headless" default="false"/>
|
||||
<!-- gazebo configs -->
|
||||
<arg name="gui" default="true"/>
|
||||
<arg name="ns" default="/"/>
|
||||
|
||||
<arg name="debug" default="false"/>
|
||||
<arg name="verbose" default="false"/>
|
||||
<arg name="paused" default="false"/>
|
||||
<arg name="respawn_gazebo" default="false"/>
|
||||
|
||||
<node name="sitl" pkg="px4" type="px4" output="screen"
|
||||
args="$(find px4) $(arg rcS)">
|
||||
</node>
|
||||
|
||||
<!-- PX4 SITL -->
|
||||
<node name="sitl" pkg="px4" type="px4" output="screen" args="$(find px4) $(arg rcS)"/>
|
||||
<!-- Gazebo sim -->
|
||||
<include file="$(find gazebo_ros)/launch/empty_world.launch">
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="world_name" value="$(arg world)" />
|
||||
<arg name="debug" value="$(arg debug)" />
|
||||
<arg name="verbose" value="$(arg verbose)" />
|
||||
<arg name="paused" value="$(arg paused)" />
|
||||
<arg name="world_name" value="$(arg world)"/>
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
<arg name="verbose" value="$(arg verbose)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
|
||||
</include>
|
||||
|
||||
<node name="$(anon vehicle_spawn)" output="screen" pkg="gazebo_ros" type="spawn_model"
|
||||
args="-sdf -file $(arg sdf) -model $(arg vehicle) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
|
||||
|
||||
|
||||
<!-- gazebo model -->
|
||||
<node name="$(anon vehicle_spawn)" pkg="gazebo_ros" type="spawn_model" output="screen" args="-sdf -file $(arg sdf) -model $(arg vehicle) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
|
||||
</launch>
|
||||
|
||||
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
|
||||
|
|
|
@ -1,33 +1,26 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
|
||||
<!-- Posix SITL environment launch script -->
|
||||
<!-- launchs PX4 SITL and spawns vehicle -->
|
||||
<!-- vehicle pose -->
|
||||
<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"/>
|
||||
<!-- vehcile model and config -->
|
||||
<arg name="est" default="ekf2"/>
|
||||
<arg name="vehicle" default="iris"/>
|
||||
<arg name="ID" default="1"/>
|
||||
<arg name="rcS" default="$(find px4)/posix-configs/SITL/init/$(arg est)/$(arg vehicle)_$(arg ID)"/>
|
||||
<arg name="mavlink_udp_port" default="14560" />
|
||||
|
||||
|
||||
|
||||
<arg name="mavlink_udp_port" default="14560"/>
|
||||
<!-- generate urdf vehicle model -->
|
||||
<arg name="cmd" default="$(find xacro)/xacro $(find px4)/Tools/sitl_gazebo/models/rotors_description/urdf/$(arg vehicle)_base.xacro rotors_description_dir:=$(find px4)/Tools/sitl_gazebo/models/rotors_description mavlink_udp_port:=$(arg mavlink_udp_port) --inorder"/>
|
||||
|
||||
|
||||
<param command="$(arg cmd)" name="rotors_description" />
|
||||
|
||||
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen"
|
||||
args="$(find px4) $(arg rcS)">
|
||||
<param command="$(arg cmd)" name="rotors_description"/>
|
||||
<!-- PX4 SITL -->
|
||||
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen" args="$(find px4) $(arg rcS)">
|
||||
</node>
|
||||
|
||||
<node name="$(arg vehicle)_$(arg ID)_spawn" output="screen" pkg="gazebo_ros" type="spawn_model"
|
||||
args="-urdf -param rotors_description -model $(arg vehicle)_$(arg ID) -package_to_model -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
|
||||
|
||||
|
||||
<!-- spawn vehicle -->
|
||||
<node name="$(arg vehicle)_$(arg ID)_spawn" output="screen" pkg="gazebo_ros" type="spawn_model" args="-urdf -param rotors_description -model $(arg vehicle)_$(arg ID) -package_to_model -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)"/>
|
||||
</launch>
|
||||
|
||||
<!-- vim: set et ft=xml fenc=utf-8 ff=unix sts=0 sw=4 ts=4 : -->
|
|
@ -1,24 +1,19 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Posix SITL MAVROS integration tests -->
|
||||
|
||||
<arg name="ns" default="/"/>
|
||||
<arg name="headless" default="true"/>
|
||||
<!-- Test a mission -->
|
||||
<arg name="gui" default="false"/>
|
||||
<arg name="est" default="ekf2"/>
|
||||
<arg name="mission"/>
|
||||
<arg name="vehicle"/>
|
||||
<arg name="respawn_gazebo" default="true"/>
|
||||
|
||||
<!-- MAVROS, PX4 SITL, Gazebo -->
|
||||
<include file="$(find px4)/launch/mavros_posix_sitl.launch">
|
||||
<arg name="ns" value="$(arg ns)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="vehicle" value="$(arg vehicle)"/>
|
||||
<arg name="est" value="$(arg est)"/>
|
||||
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<test test-name="mission_test" pkg="px4" type="mission_test.py" time-limit="300.0" args="$(arg mission)" />
|
||||
</group>
|
||||
<!-- ROStest -->
|
||||
<test test-name="mission_test" pkg="px4" type="mission_test.py" time-limit="300.0" args="$(arg mission)"/>
|
||||
</launch>
|
||||
|
|
|
@ -1,23 +1,18 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Posix SITL MAVROS integration tests -->
|
||||
|
||||
<arg name="ns" default="/"/>
|
||||
<arg name="headless" default="true"/>
|
||||
<!-- Test offboard local posistion and attitude control with optical flow iris -->
|
||||
<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="ns" value="$(arg ns)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="vehicle" value="iris_opt_flow"/>
|
||||
<arg name="est" value="$(arg est)"/>
|
||||
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<test test-name="mavros_flow_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" time-limit="120.0" />
|
||||
<test test-name="mavros_flow_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" />
|
||||
</group>
|
||||
<!-- ROStest -->
|
||||
<test test-name="mavros_flow_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" time-limit="120.0"/>
|
||||
<test test-name="mavros_flow_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" time-limit="120.0"/>
|
||||
</launch>
|
||||
|
|
|
@ -1,27 +1,22 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Posix SITL MAVROS integration tests -->
|
||||
|
||||
<arg name="ns" default="/"/>
|
||||
<arg name="headless" default="true"/>
|
||||
<!-- 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="ns" value="$(arg ns)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<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>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<test test-name="multicopter_box" pkg="px4" type="mission_test.py" time-limit="120.0" args="multirotor_box.mission"/>
|
||||
<test test-name="mission_test_new_1" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_new_1.txt"/>
|
||||
<test test-name="mission_test_new_2" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_new_2.txt"/>
|
||||
<test test-name="mission_test_old_1" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_1.txt"/>
|
||||
<test test-name="mission_test_old_2" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_2.txt"/>
|
||||
<test test-name="mission_test_old_3" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_3.txt"/>
|
||||
</group>
|
||||
<!-- ROStest -->
|
||||
<test test-name="multicopter_box" pkg="px4" type="mission_test.py" time-limit="120.0" args="multirotor_box.mission"/>
|
||||
<test test-name="mission_test_new_1" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_new_1.txt"/>
|
||||
<test test-name="mission_test_new_2" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_new_2.txt"/>
|
||||
<test test-name="mission_test_old_1" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_1.txt"/>
|
||||
<test test-name="mission_test_old_2" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_2.txt"/>
|
||||
<test test-name="mission_test_old_3" pkg="px4" type="mission_test.py" time-limit="300.0" args="vtol_old_3.txt"/>
|
||||
</launch>
|
||||
|
|
|
@ -1,22 +1,17 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Posix SITL MAVROS integration tests -->
|
||||
|
||||
<arg name="ns" default="/"/>
|
||||
<arg name="headless" default="true"/>
|
||||
<!-- Test offboard attitude control with iris -->
|
||||
<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="ns" value="$(arg ns)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="vehicle" value="iris"/>
|
||||
<arg name="est" value="$(arg est)"/>
|
||||
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<test test-name="mavros_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" time-limit="120.0"/>
|
||||
</group>
|
||||
<!-- ROStest -->
|
||||
<test test-name="mavros_offboard_attctl_test" pkg="px4" type="mavros_offboard_attctl_test.py" time-limit="120.0"/>
|
||||
</launch>
|
||||
|
|
|
@ -1,22 +1,17 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Posix SITL MAVROS integration tests -->
|
||||
|
||||
<arg name="ns" default="/"/>
|
||||
<arg name="headless" default="true"/>
|
||||
<!-- Test offboard local posistion control with iris -->
|
||||
<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="ns" value="$(arg ns)"/>
|
||||
<arg name="headless" value="$(arg headless)"/>
|
||||
<arg name="gui" value="$(arg gui)"/>
|
||||
<arg name="vehicle" value="iris"/>
|
||||
<arg name="est" value="$(arg est)"/>
|
||||
<arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
|
||||
</include>
|
||||
|
||||
<group ns="$(arg ns)">
|
||||
<test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" time-limit="120.0"/>
|
||||
</group>
|
||||
<!-- ROStest -->
|
||||
<test test-name="mavros_offboard_posctl_test" pkg="px4" type="mavros_offboard_posctl_test.py" time-limit="120.0"/>
|
||||
</launch>
|
||||
|
|
Loading…
Reference in New Issue