From 4aae95bf3e9ccc294843977c820b947d6e6cef29 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 10 Feb 2022 16:42:58 +1100 Subject: [PATCH] Revert "AP_RCProtocol: raise SBUS frame gap" This reverts commit af654f0cb766cd6156cb05ae299b96cb8afee795. this does not work with some SBUS receivers --- libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp index 54ddbdaeb6..922ccc048c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp @@ -170,7 +170,7 @@ void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1) // support byte input void AP_RCProtocol_SBUS::_process_byte(uint32_t timestamp_us, uint8_t b) { - const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 4000U); + const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 2000U); byte_input.last_byte_us = timestamp_us; if (have_frame_gap) {