Browse Source

launch: count multi UAVs from 0

This fixes the IDs of multi UAVs started with ROS/Gazebo.

Previously the 3 vehicles were displayed in QGC as Vehicle 2, 3, 4.
With this change it is more intuitive Vehicle 1, 2, 3 and this is
also consistent with the way it is documented and how it is in
jMAVSim.
sbg
Julian Oes 6 years ago committed by Lorenz Meier
parent
commit
79651ed6a4
  1. 39
      launch/multi_uav_mavros_sitl.launch

39
launch/multi_uav_mavros_sitl.launch

@ -19,11 +19,11 @@ @@ -19,11 +19,11 @@
<arg name="verbose" value="$(arg verbose)"/>
<arg name="paused" value="$(arg paused)"/>
</include>
<!-- UAV1 -->
<group ns="uav1">
<!-- UAV0 -->
<group ns="uav0">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="1"/>
<arg name="fcu_url" default="udp://:14541@localhost:14581"/>
<arg name="ID" value="0"/>
<arg name="fcu_url" default="udp://:14540@localhost:14580"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
<arg name="x" value="0"/>
@ -33,23 +33,23 @@ @@ -33,23 +33,23 @@
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="mavlink_udp_port" value="14561"/>
<arg name="mavlink_tcp_port" value="4561"/>
<arg name="mavlink_udp_port" value="14560"/>
<arg name="mavlink_tcp_port" value="4560"/>
<arg name="ID" value="$(arg ID)"/>
</include>
<!-- 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="$(eval 1 + arg('ID'))"/>
<arg name="tgt_system" value="$(eval 0 + arg('ID'))"/>
<arg name="tgt_component" value="1"/>
</include>
</group>
<!-- UAV2 -->
<group ns="uav2">
<!-- UAV1 -->
<group ns="uav1">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="2"/>
<arg name="fcu_url" default="udp://:14542@localhost:14582"/>
<arg name="ID" value="1"/>
<arg name="fcu_url" default="udp://:14541@localhost:14581"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
<arg name="x" value="1"/>
@ -59,8 +59,8 @@ @@ -59,8 +59,8 @@
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="mavlink_udp_port" value="14562"/>
<arg name="mavlink_tcp_port" value="4562"/>
<arg name="mavlink_udp_port" value="14561"/>
<arg name="mavlink_tcp_port" value="4561"/>
<arg name="ID" value="$(arg ID)"/>
</include>
<!-- MAVROS -->
@ -71,12 +71,11 @@ @@ -71,12 +71,11 @@
<arg name="tgt_component" value="1"/>
</include>
</group>
<!-- UAV3 -->
<group ns="uav3">
<!-- UAV2 -->
<group ns="uav2">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="3"/>
<arg name="fcu_url" default="udp://:14543@localhost:14583"/>
<arg name="ID" value="2"/>
<arg name="fcu_url" default="udp://:14542@localhost:14582"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
<arg name="x" value="0"/>
@ -86,8 +85,8 @@ @@ -86,8 +85,8 @@
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/>
<arg name="mavlink_udp_port" value="14563"/>
<arg name="mavlink_tcp_port" value="4563"/>
<arg name="mavlink_udp_port" value="14562"/>
<arg name="mavlink_tcp_port" value="4562"/>
<arg name="ID" value="$(arg ID)"/>
</include>
<!-- MAVROS -->

Loading…
Cancel
Save