mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_RCProtocol: increased robustness of SBUS parsing
take full advantage of the frame gap to reduce CPU and the chance of a bad decode
This commit is contained in:
parent
69c4fb671e
commit
d4c2945a48
@ -226,11 +226,22 @@ 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)
|
||||
{
|
||||
if (timestamp_us - byte_input.last_byte_us > 2000U ||
|
||||
const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us > 2000U);
|
||||
if (have_frame_gap &&
|
||||
byte_input.ofs == sizeof(byte_input.buf)) {
|
||||
byte_input.ofs = 0;
|
||||
}
|
||||
byte_input.last_byte_us = timestamp_us;
|
||||
|
||||
if (b != 0x0F && byte_input.ofs == 0) {
|
||||
// definately not SBUS, missing header byte
|
||||
return;
|
||||
}
|
||||
if (byte_input.ofs == 0 && !have_frame_gap) {
|
||||
// must have a frame gap before the start of a new SBUS frame
|
||||
return;
|
||||
}
|
||||
|
||||
byte_input.buf[byte_input.ofs++] = b;
|
||||
|
||||
if (byte_input.ofs == sizeof(byte_input.buf)) {
|
||||
|
Loading…
Reference in New Issue
Block a user