diff --git a/launch/multi_uav_mavros_sitl.launch b/launch/multi_uav_mavros_sitl.launch index b000b30e52493b9fb25683e24997d052d4a4f46b..560ebd16216e9f4d1341027203f91c19fb3d9b48 100644 --- a/launch/multi_uav_mavros_sitl.launch +++ b/launch/multi_uav_mavros_sitl.launch @@ -34,6 +34,7 @@ <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="ID" value="$(arg ID)"/> </include> <!-- MAVROS --> @@ -59,6 +60,7 @@ <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="ID" value="$(arg ID)"/> </include> <!-- MAVROS --> @@ -85,6 +87,7 @@ <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 --> diff --git a/launch/single_vehicle_spawn.launch b/launch/single_vehicle_spawn.launch index 7fe1d0b49252acb71cc6430c12c856fb5ad38ebc..ae2fbf184c01c8b0f22761c2ad1a39fe12204d36 100644 --- a/launch/single_vehicle_spawn.launch +++ b/launch/single_vehicle_spawn.launch @@ -16,10 +16,11 @@ <env name="PX4_SIM_MODEL" value="$(arg vehicle)" /> <env name="PX4_ESTIMATOR" value="$(arg est)" /> <arg name="mavlink_udp_port" default="14560"/> + <arg name="mavlink_tcp_port" default="4560"/> <!-- PX4 configs --> <arg name="interactive" default="true"/> <!-- 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"/> <!-- PX4 SITL --> <arg unless="$(arg interactive)" name="px4_command_arg1" value=""/>