From 2dd58c8ed1bc590fb596ac9d6c4c778730bf33a9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Oct 2020 10:29:51 +1100 Subject: [PATCH] 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 --- libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp index 0b3ee496db..18ca24044c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp @@ -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; }