Merge branch 'master' of gitee.com:robin_shaun/XTDrone

This commit is contained in:
Robin Shaun 2020-05-18 23:42:58 +08:00
commit 2ea9790f37
2 changed files with 273 additions and 38 deletions

View File

@ -1,4 +1,4 @@
#-*-codinggbk-*-
import sys
welcome_msg = """
@ -52,11 +52,13 @@ print(welcome_msg)
TYPE_ID = 4
num_of_all = 0
num_of_type = [0]*8
row_of_type = [0]*8
while TYPE_ID != 'f':
TYPE_ID = input(input_msg)
if TYPE_ID>='0' and TYPE_ID<='7':
num_of_type[int(TYPE_ID)] = int( input("Enter the num of "+ID_TYPE_DICT[int(TYPE_ID)]+" :" ) )
num_of_type[int(TYPE_ID)] += int( input("Enter the num of "+ID_TYPE_DICT[int(TYPE_ID)]+" :" ) )
row_of_type[int(TYPE_ID)] += int( input("Enter the row num of "+ID_TYPE_DICT[int(TYPE_ID)]+" :" ) )
elif TYPE_ID == 'f':
for i in range(7):
if num_of_type[i] != 0:
@ -65,7 +67,7 @@ while TYPE_ID != 'f':
else:
print("error!please enter a id_in_allber between 0 to 7!")
num_of_all = sum(num_of_type)
sum_of_row = sum(row_of_type)
@ -80,11 +82,11 @@ with open('launch_temp_1.11','r') as f:
with open('multi_vehicle.launch','w') as f:
f.write(launch_head)
row_num = 0
row_in_all = 0
id_in_all = 0
for type_id in range(8):
type_num = num_of_type[type_id]
row_in_type = row_of_type[type_id]
sdf_name = ID_TYPE_DICT[type_id]
# For example,
# While "iris_stereo_camera" is the model name,
@ -96,7 +98,7 @@ with open('multi_vehicle.launch','w') as f:
type_name = sdf_name.split('_')[0]
if type_num > 0:
row_num +=1
for id_in_type in range(0,type_num):
mavlink_1=34570-1+id_in_all*2
@ -124,13 +126,14 @@ with open('multi_vehicle.launch','w') as f:
elif '''<arg name="sdf" value=''' in line:
f.write(''' <arg name="sdf" value="%s"/>\n'''%sdf_name)
elif '''name="x"''' in line:
f.write(''' <arg name="x" value="%d"/>\n'''%( (row_num-1)*3 ) )
f.write(''' <arg name="x" value="%d"/>\n'''%(row_in_all*3 + ( id_in_type//row_in_type +1)*3 ) )
elif '''name="y"''' in line:
f.write(''' <arg name="y" value="%d"/>\n''' %(id_in_type*3) )
f.write(''' <arg name="y" value="%d"/>\n''' %((id_in_type%row_in_type +1)*3) )
else:
f.write('%s' %line)
f.write("\n")
id_in_all+=1
row_in_all += row_in_type

View File

@ -26,14 +26,14 @@
<arg name="fcu_url" default="udp://:14540@127.0.0.1:34570"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="0"/>
<arg name="x" value="3"/>
<arg name="y" value="3"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="vehicle" value="rover"/>
<arg name="sdf" value="rover_with_sensors"/>
<arg name="mavlink_udp_port" value="24560"/>
<arg name="mavlink_tcp_port" value="4560"/>
<arg name="ID" value="$(arg ID)"/>
@ -47,22 +47,22 @@
<arg name="tgt_component" value="1"/>
</include>
</group>
<!-- iris_1 -->
<group ns="iris_1">
<!-- rover_1 -->
<group ns="rover_1">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="1"/>
<arg name="ID_in_group" value="1"/>
<arg name="fcu_url" default="udp://:14541@127.0.0.1:34572"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="3"/>
<arg name="x" value="3"/>
<arg name="y" value="6"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="vehicle" value="rover"/>
<arg name="sdf" value="rover_with_sensors"/>
<arg name="mavlink_udp_port" value="24562"/>
<arg name="mavlink_tcp_port" value="4561"/>
<arg name="ID" value="$(arg ID)"/>
@ -76,22 +76,22 @@
<arg name="tgt_component" value="1"/>
</include>
</group>
<!-- iris_2 -->
<group ns="iris_2">
<!-- rover_2 -->
<group ns="rover_2">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="2"/>
<arg name="ID_in_group" value="2"/>
<arg name="fcu_url" default="udp://:14542@127.0.0.1:34574"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="6"/>
<arg name="x" value="3"/>
<arg name="y" value="9"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="vehicle" value="rover"/>
<arg name="sdf" value="rover_with_sensors"/>
<arg name="mavlink_udp_port" value="24564"/>
<arg name="mavlink_tcp_port" value="4562"/>
<arg name="ID" value="$(arg ID)"/>
@ -105,22 +105,22 @@
<arg name="tgt_component" value="1"/>
</include>
</group>
<!-- iris_3 -->
<group ns="iris_3">
<!-- rover_3 -->
<group ns="rover_3">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="3"/>
<arg name="ID_in_group" value="3"/>
<arg name="fcu_url" default="udp://:14543@127.0.0.1:34576"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="9"/>
<arg name="x" value="6"/>
<arg name="y" value="3"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="vehicle" value="rover"/>
<arg name="sdf" value="rover_with_sensors"/>
<arg name="mavlink_udp_port" value="24566"/>
<arg name="mavlink_tcp_port" value="4563"/>
<arg name="ID" value="$(arg ID)"/>
@ -134,24 +134,256 @@
<arg name="tgt_component" value="1"/>
</include>
</group>
<!-- iris_4 -->
<group ns="iris_4">
<!-- typhoon_h480_0 -->
<group ns="typhoon_h480_0">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="4"/>
<arg name="ID_in_group" value="4"/>
<arg name="ID_in_group" value="0"/>
<arg name="fcu_url" default="udp://:14544@127.0.0.1:34578"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="x" value="12"/>
<arg name="y" value="3"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="typhoon_h480"/>
<arg name="sdf" value="typhoon_h480_stereo"/>
<arg name="mavlink_udp_port" value="24568"/>
<arg name="mavlink_tcp_port" value="4564"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- typhoon_h480_1 -->
<group ns="typhoon_h480_1">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="5"/>
<arg name="ID_in_group" value="1"/>
<arg name="fcu_url" default="udp://:14545@127.0.0.1:34580"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="12"/>
<arg name="y" value="6"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="typhoon_h480"/>
<arg name="sdf" value="typhoon_h480_stereo"/>
<arg name="mavlink_udp_port" value="24570"/>
<arg name="mavlink_tcp_port" value="4565"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- typhoon_h480_2 -->
<group ns="typhoon_h480_2">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="6"/>
<arg name="ID_in_group" value="2"/>
<arg name="fcu_url" default="udp://:14546@127.0.0.1:34582"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="12"/>
<arg name="y" value="9"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="typhoon_h480"/>
<arg name="sdf" value="typhoon_h480_stereo"/>
<arg name="mavlink_udp_port" value="24572"/>
<arg name="mavlink_tcp_port" value="4566"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- typhoon_h480_3 -->
<group ns="typhoon_h480_3">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="7"/>
<arg name="ID_in_group" value="3"/>
<arg name="fcu_url" default="udp://:14547@127.0.0.1:34584"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="12"/>
<arg name="y" value="12"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="mavlink_udp_port" value="24568"/>
<arg name="mavlink_tcp_port" value="4564"/>
<arg name="vehicle" value="typhoon_h480"/>
<arg name="sdf" value="typhoon_h480_stereo"/>
<arg name="mavlink_udp_port" value="24574"/>
<arg name="mavlink_tcp_port" value="4567"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- solo_0 -->
<group ns="solo_0">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="8"/>
<arg name="ID_in_group" value="0"/>
<arg name="fcu_url" default="udp://:14548@127.0.0.1:34586"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="24"/>
<arg name="y" value="3"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="solo"/>
<arg name="sdf" value="solo_stereo_camera"/>
<arg name="mavlink_udp_port" value="24576"/>
<arg name="mavlink_tcp_port" value="4568"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- solo_1 -->
<group ns="solo_1">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="9"/>
<arg name="ID_in_group" value="1"/>
<arg name="fcu_url" default="udp://:14549@127.0.0.1:34588"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="24"/>
<arg name="y" value="6"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="solo"/>
<arg name="sdf" value="solo_stereo_camera"/>
<arg name="mavlink_udp_port" value="24578"/>
<arg name="mavlink_tcp_port" value="4569"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- solo_2 -->
<group ns="solo_2">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="10"/>
<arg name="ID_in_group" value="2"/>
<arg name="fcu_url" default="udp://:14550@127.0.0.1:34590"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="27"/>
<arg name="y" value="3"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="solo"/>
<arg name="sdf" value="solo_stereo_camera"/>
<arg name="mavlink_udp_port" value="24580"/>
<arg name="mavlink_tcp_port" value="4570"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- solo_3 -->
<group ns="solo_3">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="11"/>
<arg name="ID_in_group" value="3"/>
<arg name="fcu_url" default="udp://:14551@127.0.0.1:34592"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="27"/>
<arg name="y" value="6"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="solo"/>
<arg name="sdf" value="solo_stereo_camera"/>
<arg name="mavlink_udp_port" value="24582"/>
<arg name="mavlink_tcp_port" value="4571"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</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>
<!-- solo_4 -->
<group ns="solo_4">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="12"/>
<arg name="ID_in_group" value="4"/>
<arg name="fcu_url" default="udp://:14552@127.0.0.1:34594"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="30"/>
<arg name="y" value="3"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
<arg name="P" value="0"/>
<arg name="Y" value="0"/>
<arg name="vehicle" value="solo"/>
<arg name="sdf" value="solo_stereo_camera"/>
<arg name="mavlink_udp_port" value="24584"/>
<arg name="mavlink_tcp_port" value="4572"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</include>