Browse Source

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
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
af9e96c619
  1. 2
      libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp

2
libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp

@ -72,7 +72,7 @@ @@ -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

Loading…
Cancel
Save