add mavlink_tcp_port for multiple uav simultation

This commit is contained in:
stmoon 2019-02-17 07:24:00 +00:00 committed by Beat Küng
parent 4dc1503122
commit 460c16cd7a
2 changed files with 5 additions and 1 deletions

View File

@ -34,6 +34,7 @@
<arg name="Y" value="0"/> <arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/> <arg name="vehicle" value="$(arg vehicle)"/>
<arg name="mavlink_udp_port" value="14561"/> <arg name="mavlink_udp_port" value="14561"/>
<arg name="mavlink_tcp_port" value="4561"/>
<arg name="ID" value="$(arg ID)"/> <arg name="ID" value="$(arg ID)"/>
</include> </include>
<!-- MAVROS --> <!-- MAVROS -->
@ -59,6 +60,7 @@
<arg name="Y" value="0"/> <arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/> <arg name="vehicle" value="$(arg vehicle)"/>
<arg name="mavlink_udp_port" value="14562"/> <arg name="mavlink_udp_port" value="14562"/>
<arg name="mavlink_tcp_port" value="4562"/>
<arg name="ID" value="$(arg ID)"/> <arg name="ID" value="$(arg ID)"/>
</include> </include>
<!-- MAVROS --> <!-- MAVROS -->
@ -85,6 +87,7 @@
<arg name="Y" value="0"/> <arg name="Y" value="0"/>
<arg name="vehicle" value="$(arg vehicle)"/> <arg name="vehicle" value="$(arg vehicle)"/>
<arg name="mavlink_udp_port" value="14563"/> <arg name="mavlink_udp_port" value="14563"/>
<arg name="mavlink_tcp_port" value="4563"/>
<arg name="ID" value="$(arg ID)"/> <arg name="ID" value="$(arg ID)"/>
</include> </include>
<!-- MAVROS --> <!-- MAVROS -->

View File

@ -16,10 +16,11 @@
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" /> <env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
<env name="PX4_ESTIMATOR" value="$(arg est)" /> <env name="PX4_ESTIMATOR" value="$(arg est)" />
<arg name="mavlink_udp_port" default="14560"/> <arg name="mavlink_udp_port" default="14560"/>
<arg name="mavlink_tcp_port" default="4560"/>
<!-- PX4 configs --> <!-- PX4 configs -->
<arg name="interactive" default="true"/> <arg name="interactive" default="true"/>
<!-- generate urdf vehicle model --> <!-- 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"/> <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) mavlink_tcp_port:=$(arg mavlink_tcp_port) --inorder"/>
<param command="$(arg cmd)" name="rotors_description"/> <param command="$(arg cmd)" name="rotors_description"/>
<!-- PX4 SITL --> <!-- PX4 SITL -->
<arg unless="$(arg interactive)" name="px4_command_arg1" value=""/> <arg unless="$(arg interactive)" name="px4_command_arg1" value=""/>