mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
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:
parent
3b50123f18
commit
87c767df5c
@ -225,7 +225,7 @@ bool AP_RCProtocol::process_byte(uint8_t byte, uint32_t baudrate)
|
||||
}
|
||||
// stop decoding pulses to save CPU
|
||||
hal.rcin->pulse_input_enable(false);
|
||||
break;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user