From 7716754c6100637470edea86c84aba0099d44758 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 10 Feb 2022 16:47:02 +1100 Subject: [PATCH] Revert "AP_RCProtocol: change default SBUS frame gap to 4ms" This reverts commit af9e96c61970e14f1d03d80e331a584d4579de43. revert as this causes a problem on some receivers such as the Frsky R9 fixes #19899 --- 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 f4cd31e92a..1ab64ffc99 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp @@ -72,7 +72,7 @@ #define SBUS_SCALE_OFFSET (SBUS_TARGET_MIN - ((SBUS_TARGET_RANGE * SBUS_RANGE_MIN / SBUS_RANGE_RANGE))) #ifndef HAL_SBUS_FRAME_GAP -#define HAL_SBUS_FRAME_GAP 4000U +#define HAL_SBUS_FRAME_GAP 2000U #endif // constructor