mirror of https://github.com/ArduPilot/ardupilot
Revert "AP_RCProtocol: raise SBUS frame gap"
This reverts commit af654f0cb7
.
this does not work with some SBUS receivers
This commit is contained in:
parent
cbea3bc471
commit
4aae95bf3e
|
@ -170,7 +170,7 @@ void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
|||
// support byte input
|
||||
void AP_RCProtocol_SBUS::_process_byte(uint32_t timestamp_us, uint8_t b)
|
||||
{
|
||||
const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 4000U);
|
||||
const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 2000U);
|
||||
byte_input.last_byte_us = timestamp_us;
|
||||
|
||||
if (have_frame_gap) {
|
||||
|
|
Loading…
Reference in New Issue