From af654f0cb766cd6156cb05ae299b96cb8afee795 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 27 Jan 2022 15:56:24 +1100 Subject: [PATCH] AP_RCProtocol: raise SBUS frame gap cope with UART input for newer 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 922ccc048c..54ddbdaeb6 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 >= 2000U); + const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 4000U); byte_input.last_byte_us = timestamp_us; if (have_frame_gap) {