mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: AP_Periph: Reduce the priority of outdoing ADS-B messages
We consume these at line rate from the transciever, don't allow this to cause unnecessary congestion on the bus, as it may be used for flight critical functions. A more proper solution would be to behave more like the actual AP_ADSB library, and simple rate limit how often we send any updates out to the host device, as well as filtering for distance, but that requires more information then is currently readily available.
This commit is contained in:
parent
aff1247f30
commit
584a1f8c49
@ -2473,7 +2473,7 @@ void AP_Periph_FW::can_send_ADSB(struct __mavlink_adsb_vehicle_t &msg)
|
||||
|
||||
canard_broadcast(ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_SIGNATURE,
|
||||
ARDUPILOT_EQUIPMENT_TRAFFICMONITOR_TRAFFICREPORT_ID,
|
||||
CANARD_TRANSFER_PRIORITY_LOW,
|
||||
CANARD_TRANSFER_PRIORITY_LOWEST,
|
||||
&buffer[0],
|
||||
total_size);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user