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
This commit is contained in:
Andrew Tridgell 2022-01-27 15:12:11 +11:00
parent d1bf4f1c1e
commit af9e96c619

View File

@ -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