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:
Michael du Breuil 2023-05-24 13:14:17 -07:00 committed by Tom Pittenger
parent aff1247f30
commit 584a1f8c49
1 changed files with 1 additions and 1 deletions

View File

@ -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);
}