fix more than 10 vehicle can not connect the MAVROS

This commit is contained in:
Shaochang Tan 2020-09-20 21:21:09 +08:00
parent 6e96f9db3e
commit 519aa55235
5 changed files with 565 additions and 84 deletions

3
.gitignore vendored
View File

@ -6,4 +6,5 @@ project
*.pbstream
sensing/slam/vio/VINS-Fusion/camera_models/camera_calib_example
.gitee
.vscode
.vscode
.idea

View File

@ -82,7 +82,7 @@ with open('launch_temp_1.11','r') as f:
with open('multi_vehicle.launch','w') as f:
f.write(launch_head)
row_in_all = 0
id_in_all = 1
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]
@ -100,11 +100,9 @@ with open('multi_vehicle.launch','w') as f:
if type_num > 0:
for id_in_type in range(0,type_num):
mavlink_1=34570-1+id_in_all*2
mavlink_2=mavlink_1+1
onboard=14540+id_in_all
SITL=24560+(id_in_all)*2
offboard_local=34580+id_in_all
offboard_remote=24540+id_in_all
SITL=18570+id_in_all
TCP=4560+id_in_all
for line in launch_lines:
if "<!-- UAV" in line:
@ -116,7 +114,7 @@ with open('multi_vehicle.launch','w') as f:
elif '''<arg name="ID_in_group" value="0"/>''' in line:
f.write(''' <arg name="ID_in_group" value="%d"/>\n''' %id_in_type)
elif "udp://:" in line:
f.write(''' <arg name="fcu_url" default="udp://:%d@localhost:%d"/>\n''' %(onboard,mavlink_2))
f.write(''' <arg name="fcu_url" default="udp://:%d@localhost:%d"/>\n''' %(offboard_remote,offboard_local))
elif "mavlink_udp_port" in line:
f.write(''' <arg name="mavlink_udp_port" value="%d"/>\n'''%SITL)
elif "mavlink_tcp_port" in line:

View File

@ -21,9 +21,9 @@
<!-- iris_0 -->
<group ns="iris_0">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="1"/>
<arg name="ID" value="0"/>
<arg name="ID_in_group" value="0"/>
<arg name="fcu_url" default="udp://:14541@localhost:34572"/>
<arg name="fcu_url" default="udp://:24540@localhost:34580"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
@ -34,8 +34,8 @@
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="mavlink_udp_port" value="24562"/>
<arg name="mavlink_tcp_port" value="4561"/>
<arg name="mavlink_udp_port" value="18570"/>
<arg name="mavlink_tcp_port" value="4560"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</include>
@ -50,9 +50,9 @@
<!-- iris_1 -->
<group ns="iris_1">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="2"/>
<arg name="ID" value="1"/>
<arg name="ID_in_group" value="1"/>
<arg name="fcu_url" default="udp://:14542@localhost:34574"/>
<arg name="fcu_url" default="udp://:24541@localhost:34581"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
@ -63,8 +63,8 @@
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="mavlink_udp_port" value="24564"/>
<arg name="mavlink_tcp_port" value="4562"/>
<arg name="mavlink_udp_port" value="18571"/>
<arg name="mavlink_tcp_port" value="4561"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</include>
@ -79,21 +79,21 @@
<!-- iris_2 -->
<group ns="iris_2">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="3"/>
<arg name="ID" value="2"/>
<arg name="ID_in_group" value="2"/>
<arg name="fcu_url" default="udp://:14543@localhost:34576"/>
<arg name="fcu_url" default="udp://:24542@localhost:34582"/>
<!-- 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="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="mavlink_udp_port" value="24566"/>
<arg name="mavlink_tcp_port" value="4563"/>
<arg name="mavlink_udp_port" value="18572"/>
<arg name="mavlink_tcp_port" value="4562"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</include>
@ -108,12 +108,12 @@
<!-- iris_3 -->
<group ns="iris_3">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="4"/>
<arg name="ID" value="3"/>
<arg name="ID_in_group" value="3"/>
<arg name="fcu_url" default="udp://:14544@localhost:34578"/>
<arg name="fcu_url" default="udp://:24543@localhost:34583"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
<arg name="x" value="0"/>
<arg name="y" value="6"/>
<arg name="z" value="0"/>
<arg name="R" value="0"/>
@ -121,8 +121,8 @@
<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="mavlink_udp_port" value="18573"/>
<arg name="mavlink_tcp_port" value="4563"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</include>
@ -137,21 +137,21 @@
<!-- iris_4 -->
<group ns="iris_4">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="5"/>
<arg name="ID" value="4"/>
<arg name="ID_in_group" value="4"/>
<arg name="fcu_url" default="udp://:14545@localhost:34580"/>
<arg name="fcu_url" default="udp://:24544@localhost:34584"/>
<!-- 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="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="mavlink_udp_port" value="24570"/>
<arg name="mavlink_tcp_port" value="4565"/>
<arg name="mavlink_udp_port" value="18574"/>
<arg name="mavlink_tcp_port" value="4564"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</include>
@ -166,9 +166,67 @@
<!-- iris_5 -->
<group ns="iris_5">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="6"/>
<arg name="ID" value="5"/>
<arg name="ID_in_group" value="5"/>
<arg name="fcu_url" default="udp://:14546@localhost:34582"/>
<arg name="fcu_url" default="udp://:24545@localhost:34585"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="6"/>
<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="mavlink_udp_port" value="18575"/>
<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>
<!-- iris_6 -->
<group ns="iris_6">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="6"/>
<arg name="ID_in_group" value="6"/>
<arg name="fcu_url" default="udp://:24546@localhost:34586"/>
<!-- 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="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="18576"/>
<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>
<!-- iris_7 -->
<group ns="iris_7">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="7"/>
<arg name="ID_in_group" value="7"/>
<arg name="fcu_url" default="udp://:24547@localhost:34587"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
@ -179,8 +237,443 @@
<arg name="Y" value="0"/>
<arg name="vehicle" value="iris"/>
<arg name="sdf" value="iris_stereo_camera"/>
<arg name="mavlink_udp_port" value="24572"/>
<arg name="mavlink_tcp_port" value="4566"/>
<arg name="mavlink_udp_port" value="18577"/>
<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>
<!-- iris_8 -->
<group ns="iris_8">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="8"/>
<arg name="ID_in_group" value="8"/>
<arg name="fcu_url" default="udp://:24548@localhost:34588"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="6"/>
<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="mavlink_udp_port" value="18578"/>
<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>
<!-- iris_9 -->
<group ns="iris_9">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="9"/>
<arg name="ID_in_group" value="9"/>
<arg name="fcu_url" default="udp://:24549@localhost:34589"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<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="18579"/>
<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>
<!-- iris_10 -->
<group ns="iris_10">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="10"/>
<arg name="ID_in_group" value="10"/>
<arg name="fcu_url" default="udp://:24550@localhost:34590"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
<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="18580"/>
<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>
<!-- iris_11 -->
<group ns="iris_11">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="11"/>
<arg name="ID_in_group" value="11"/>
<arg name="fcu_url" default="udp://:24551@localhost:34591"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="6"/>
<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="18581"/>
<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>
<!-- iris_12 -->
<group ns="iris_12">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="12"/>
<arg name="ID_in_group" value="12"/>
<arg name="fcu_url" default="udp://:24552@localhost:34592"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="15"/>
<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="18582"/>
<arg name="mavlink_tcp_port" value="4572"/>
<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>
<!-- iris_13 -->
<group ns="iris_13">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="13"/>
<arg name="ID_in_group" value="13"/>
<arg name="fcu_url" default="udp://:24553@localhost:34593"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
<arg name="y" value="15"/>
<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="18583"/>
<arg name="mavlink_tcp_port" value="4573"/>
<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>
<!-- iris_14 -->
<group ns="iris_14">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="14"/>
<arg name="ID_in_group" value="14"/>
<arg name="fcu_url" default="udp://:24554@localhost:34594"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="6"/>
<arg name="y" value="15"/>
<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="18584"/>
<arg name="mavlink_tcp_port" value="4574"/>
<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>
<!-- iris_15 -->
<group ns="iris_15">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="15"/>
<arg name="ID_in_group" value="15"/>
<arg name="fcu_url" default="udp://:24555@localhost:34595"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="18"/>
<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="18585"/>
<arg name="mavlink_tcp_port" value="4575"/>
<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>
<!-- iris_16 -->
<group ns="iris_16">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="16"/>
<arg name="ID_in_group" value="16"/>
<arg name="fcu_url" default="udp://:24556@localhost:34596"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
<arg name="y" value="18"/>
<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="18586"/>
<arg name="mavlink_tcp_port" value="4576"/>
<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>
<!-- iris_17 -->
<group ns="iris_17">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="17"/>
<arg name="ID_in_group" value="17"/>
<arg name="fcu_url" default="udp://:24557@localhost:34597"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="6"/>
<arg name="y" value="18"/>
<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="18587"/>
<arg name="mavlink_tcp_port" value="4577"/>
<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>
<!-- iris_18 -->
<group ns="iris_18">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="18"/>
<arg name="ID_in_group" value="18"/>
<arg name="fcu_url" default="udp://:24558@localhost:34598"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="21"/>
<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="18588"/>
<arg name="mavlink_tcp_port" value="4578"/>
<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>
<!-- iris_19 -->
<group ns="iris_19">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="19"/>
<arg name="ID_in_group" value="19"/>
<arg name="fcu_url" default="udp://:24559@localhost:34599"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
<arg name="y" value="21"/>
<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="18589"/>
<arg name="mavlink_tcp_port" value="4579"/>
<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>
<!-- iris_20 -->
<group ns="iris_20">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="20"/>
<arg name="ID_in_group" value="20"/>
<arg name="fcu_url" default="udp://:24560@localhost:34600"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="6"/>
<arg name="y" value="21"/>
<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="18590"/>
<arg name="mavlink_tcp_port" value="4580"/>
<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>
<!-- iris_21 -->
<group ns="iris_21">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="21"/>
<arg name="ID_in_group" value="21"/>
<arg name="fcu_url" default="udp://:24561@localhost:34601"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="0"/>
<arg name="y" value="24"/>
<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="18591"/>
<arg name="mavlink_tcp_port" value="4581"/>
<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>
<!-- iris_22 -->
<group ns="iris_22">
<!-- MAVROS and vehicle configs -->
<arg name="ID" value="22"/>
<arg name="ID_in_group" value="22"/>
<arg name="fcu_url" default="udp://:24562@localhost:34602"/>
<!-- PX4 SITL and vehicle spawn -->
<include file="$(find px4)/launch/single_vehicle_spawn_xtd.launch">
<arg name="x" value="3"/>
<arg name="y" value="24"/>
<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="18592"/>
<arg name="mavlink_tcp_port" value="4582"/>
<arg name="ID" value="$(arg ID)"/>
<arg name="ID_in_group" value="$(arg ID_in_group)"/>
</include>

View File

@ -32,7 +32,8 @@ set PWM_OUT none
set SDCARD_MIXERS_PATH etc/mixers
set USE_IO no
set VEHICLE_TYPE none
set LOGGER_BUF 1000
set LOGGER_ARGS ""
set LOGGER_BUF 1000
set RUN_MINIMAL_SHELL no
@ -107,24 +108,24 @@ fi
# shellcheck disable=SC2154
param set MAV_SYS_ID $((px4_instance+1))
simulator_tcp_port=$((4560+px4_instance))
udp_offboard_port_local=$((14580+px4_instance))
udp_offboard_port_remote=$((14540+px4_instance))
[ $px4_instance -gt 9 ] && udp_offboard_port_remote=14549 # use the same ports for more than 10 instances to avoid port overlaps
udp_onboard_payload_port_local=$((14280+px4_instance))
udp_onboard_payload_port_remote=$((14030+px4_instance))
udp_offboard_port_local=$((34580+px4_instance))
udp_offboard_port_remote=$((24540+px4_instance))
#[ $px4_instance -gt 9 ] && udp_offboard_port_remote=14549 # use the same ports for more than 10 instances to avoid port overlaps
#udp_onboard_payload_port_local=$((14280+px4_instance))
#udp_onboard_payload_port_remote=$((14030+px4_instance))
udp_gcs_port_local=$((18570+px4_instance))
if [ $AUTOCNF = yes ]
then
param set SYS_AUTOSTART $REQUESTED_AUTOSTART
param set BAT_N_CELLS 3
param set BAT_N_CELLS 4
param set CAL_ACC0_ID 1311244
param set CAL_ACC_PRIME 1311244
param set CAL_GYRO0_ID 2294028
param set CAL_GYRO_PRIME 2294028
param set CAL_GYRO0_ID 1311244
param set CAL_GYRO_PRIME 1311244
param set CAL_MAG0_ID 197388
param set CAL_MAG_PRIME 197388
@ -132,21 +133,9 @@ then
param set CBRK_AIRSPD_CHK 0
param set CBRK_SUPPLY_CHK 894281
param set COM_DISARM_LAND 0.5
param set COM_OBL_ACT 2
param set COM_OBL_RC_ACT 0
# Don't require RC calibration and configuration
param set COM_RC_IN_MODE 1
# GPS used
param set EKF2_AID_MASK 1
# Vision used and GPS denied
#param set EKF2_AID_MASK 24
# Barometer used for hight measurement
param set EKF2_HGT_MODE 0
# Barometer denied and vision used for hight measurement
#param set EKF2_HGT_MODE 3
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
@ -159,31 +148,18 @@ then
# LPE: GPS only mode
param set LPE_FUSION 145
# Simulator IMU data provided at 250 Hz
param set IMU_INTEG_RATE 250
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.2
param set MPC_ALT_MODE 0
param set MPC_HOLD_MAX_Z 2
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_P 0.6
param set MPC_Z_VEL_P_ACC 12.0
param set MPC_Z_VEL_I_ACC 3.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_P 0.2
param set MPC_XY_VEL_I 0.02
param set MPC_XY_VEL_D 0.016
param set MPC_XY_VEL_P_ACC 4.0
param set MPC_XY_VEL_I_ACC 0.4
param set MPC_XY_VEL_D_ACC 0.32
param set MPC_SPOOLUP_TIME 0.5
param set MPC_TKO_RAMP_T 1
param set NAV_ACC_RAD 2
param set NAV_DLL_ACT 2
param set RTL_DESCEND_ALT 5
param set RTL_LAND_DELAY 5
param set RTL_RETURN_ALT 30
# By default log from boot until first disarm.
@ -201,8 +177,11 @@ fi
param set COM_CPU_MAX -1 # disable check, no CPU load reported on posix yet
# Simulator IMU data provided at 250 Hz
param set IMU_INTEG_RATE 250
# Adapt timeout parameters if simulation runs faster or slower than realtime.
if [ ! -z $PX4_SIM_SPEED_FACTOR ]; then
if [ -n "$PX4_SIM_SPEED_FACTOR" ]; then
COM_DL_LOSS_T_LONGER=$(echo "$PX4_SIM_SPEED_FACTOR * 10" | bc)
echo "COM_DL_LOSS_T set to $COM_DL_LOSS_T_LONGER"
param set COM_DL_LOSS_T $COM_DL_LOSS_T_LONGER
@ -246,8 +225,12 @@ then
fi
dataman start
replay tryapplyparams
simulator start -c $simulator_tcp_port
# only start the simulator if not in replay mode, as both control the lockstep time
if ! replay tryapplyparams
then
simulator start -c $simulator_tcp_port
fi
battery_simulator start
tone_alarm start
rc_update start
sensors start
@ -288,13 +271,19 @@ mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u $udp_gcs_port_local
mavlink start -x -u $udp_offboard_port_local -r 4000000 -m onboard -o $udp_offboard_port_remote
# Onboard link to camera
mavlink start -x -u $udp_onboard_payload_port_local -r 4000 -f -m onboard -o $udp_onboard_payload_port_remote
#mavlink start -x -u $udp_onboard_payload_port_local -r 4000 -f -m onboard -o $udp_onboard_payload_port_remote
# execute autostart post script if any
[ -e "$autostart_file".post ] && sh "$autostart_file".post
# Run script to start logging
if param compare SYS_MC_EST_GROUP 2
then
set LOGGER_ARGS "-p ekf2_timestamps"
else
set LOGGER_ARGS "-p vehicle_attitude"
fi
sh etc/init.d/rc.logging
mavlink boot_complete
replay trystart
replay trystart

View File

@ -10,9 +10,9 @@
<arg name="P" default="0"/>
<arg name="Y" default="0"/>
<!-- vehcile model and config -->
<arg name="sdf" default="plane"/>
<arg name="sdf" default="iris"/>
<arg name="est" default="ekf2"/>
<arg name="vehicle" default="plane"/>
<arg name="vehicle" default="iris"/>
<arg name="ID" default="0"/>
<arg name="ID_in_group" default="0"/>
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />