mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
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.
This commit is contained in:
parent
ea902e7f38
commit
2ab276f5ca
@ -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
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user