mirror of https://github.com/ArduPilot/ardupilot
Revert "AP_RCProtocol: change default SBUS frame gap to 4ms"
This reverts commit af9e96c619
.
revert as this causes a problem on some receivers such as the Frsky R9
fixes #19899
This commit is contained in:
parent
bbc040d807
commit
7716754c61
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue