AP_RCProtocol: return true on initial protocol detection

we need to tell the IO firmware that a byte was consumed when we first
detect a protocol as otherwise the next bad byte on DSM will lock us
on the DSM port
This commit is contained in:
Andrew Tridgell 2023-05-21 18:45:43 +10:00
parent 816f3d1124
commit d651395891

View File

@ -219,7 +219,7 @@ bool AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
} }
// stop decoding pulses to save CPU // stop decoding pulses to save CPU
hal.rcin->pulse_input_enable(false); hal.rcin->pulse_input_enable(false);
break; return true;
} }
} }
} }