From 2ab276f5ca3aff17e97bc30ffa6e64c968e43257 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 23 Mar 2021 15:19:56 +0100 Subject: [PATCH] ROMFS: disable MAVLink broadcast by default I don't think we should be broadcasting by default as we haven't done that in the past. This suddenly spams the network with a lot of messages, and leads to confusing situations in offices where there are multiple PX4 SITL and QGC intances are open. --- ROMFS/px4fmu_common/init.d-posix/rcS | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index cd7321b596..e56e1334bf 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -260,7 +260,7 @@ then sh etc/init.d-posix/rc.mavlink_override else # GCS link - mavlink start -x -u $udp_gcs_port_local -r 4000000 -f -p + mavlink start -x -u $udp_gcs_port_local -r 4000000 -f mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u $udp_gcs_port_local mavlink stream -r 50 -s LOCAL_POSITION_NED -u $udp_gcs_port_local mavlink stream -r 50 -s GLOBAL_POSITION_INT -u $udp_gcs_port_local @@ -272,13 +272,13 @@ else mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u $udp_gcs_port_local # API/Offboard link - mavlink start -x -u $udp_offboard_port_local -r 4000000 -f -m onboard -o $udp_offboard_port_remote -p + mavlink start -x -u $udp_offboard_port_local -r 4000000 -f -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 -p + mavlink start -x -u $udp_onboard_payload_port_local -r 4000 -f -m onboard -o $udp_onboard_payload_port_remote # Onboard link to gimbal - mavlink start -x -u $udp_onboard_gimbal_port_local -r 400000 -m gimbal -o $udp_onboard_gimbal_port_remote -p + mavlink start -x -u $udp_onboard_gimbal_port_local -r 400000 -m gimbal -o $udp_onboard_gimbal_port_remote fi # execute autostart post script if any