forked from Archive/PX4-Autopilot
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.
This commit is contained in:
parent
77097b6adc
commit
79651ed6a4
|
@ -19,6 +19,32 @@
|
|||
<arg name="verbose" value="$(arg verbose)"/>
|
||||
<arg name="paused" value="$(arg paused)"/>
|
||||
</include>
|
||||
<!-- UAV0 -->
|
||||
<group ns="uav0">
|
||||
<!-- MAVROS and vehicle configs -->
|
||||
<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"/>
|
||||
<arg name="y" value="0"/>
|
||||
<arg name="z" value="0"/>
|
||||
<arg name="R" value="0"/>
|
||||
<arg name="P" value="0"/>
|
||||
<arg name="Y" value="0"/>
|
||||
<arg name="vehicle" value="$(arg vehicle)"/>
|
||||
<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 0 + arg('ID'))"/>
|
||||
<arg name="tgt_component" value="1"/>
|
||||
</include>
|
||||
</group>
|
||||
<!-- UAV1 -->
|
||||
<group ns="uav1">
|
||||
<!-- MAVROS and vehicle configs -->
|
||||
|
@ -26,7 +52,7 @@
|
|||
<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="0"/>
|
||||
<arg name="x" value="1"/>
|
||||
<arg name="y" value="0"/>
|
||||
<arg name="z" value="0"/>
|
||||
<arg name="R" value="0"/>
|
||||
|
@ -52,8 +78,8 @@
|
|||
<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="1"/>
|
||||
<arg name="y" value="0"/>
|
||||
<arg name="x" value="0"/>
|
||||
<arg name="y" value="1"/>
|
||||
<arg name="z" value="0"/>
|
||||
<arg name="R" value="0"/>
|
||||
<arg name="P" value="0"/>
|
||||
|
@ -71,33 +97,6 @@
|
|||
<arg name="tgt_component" value="1"/>
|
||||
</include>
|
||||
</group>
|
||||
|
||||
<!-- UAV3 -->
|
||||
<group ns="uav3">
|
||||
<!-- MAVROS and vehicle configs -->
|
||||
<arg name="ID" value="3"/>
|
||||
<arg name="fcu_url" default="udp://:14543@localhost:14583"/>
|
||||
<!-- PX4 SITL and vehicle spawn -->
|
||||
<include file="$(find px4)/launch/single_vehicle_spawn.launch">
|
||||
<arg name="x" value="0"/>
|
||||
<arg name="y" value="1"/>
|
||||
<arg name="z" value="0"/>
|
||||
<arg name="R" value="0"/>
|
||||
<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="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_component" value="1"/>
|
||||
</include>
|
||||
</group>
|
||||
</launch>
|
||||
<!-- to add more UAVs (up to 10):
|
||||
Increase the id
|
||||
|
|
Loading…
Reference in New Issue