AP_RCProtocol: send null pkts for FPort2

when we have no data to send, we should send an empty packet to ensure
the receiver schedules us for data as often as possible
This commit is contained in:
Andrew Tridgell 2020-10-28 10:29:51 +11:00
parent 97b44dfe71
commit 2dd58c8ed1
1 changed files with 5 additions and 1 deletions

View File

@ -116,7 +116,11 @@ void AP_RCProtocol_FPort2::decode_downlink(const FPort2_Frame &frame)
*/
if (!telem_data.available) {
if (!AP_Frsky_Telem::get_telem_data(telem_data.frame, telem_data.appid, telem_data.data)) {
return;
// nothing to send, send a null frame. This ensures the
// receiver keeps requesting data from us at the full rate
telem_data.frame = 0x00;
telem_data.appid = 0x00;
telem_data.data = 0x00;
}
telem_data.available = true;
}