AP_RCProtocol: raise SBUS frame gap

cope with UART input for newer SBUS receivers
This commit is contained in:
Andrew Tridgell 2022-01-27 15:56:24 +11:00 committed by Randy Mackay
parent 6869a0b0a2
commit af654f0cb7
1 changed files with 1 additions and 1 deletions

View File

@ -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 >= 2000U);
const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 4000U);
byte_input.last_byte_us = timestamp_us;
if (have_frame_gap) {