From af9e96c61970e14f1d03d80e331a584d4579de43 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 27 Jan 2022 15:12:11 +1100 Subject: [PATCH] AP_RCProtocol: change default SBUS frame gap to 4ms this is to cope with some newer receivers such as the skydroid H16 which produces SBUS frames with gaps over 2ms without this change we get can RC failsafes constantly --- 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 1ab64ffc99..f4cd31e92a 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 2000U +#define HAL_SBUS_FRAME_GAP 4000U #endif // constructor