AP_RCProtocol: on DSM sync error don't reset channel count
this fixes the issue noticed by Andreyl in 3.6.5rc1
This commit is contained in:
parent
a885f86ce7
commit
3f25891fea
@ -405,7 +405,6 @@ bool AP_RCProtocol_DSM::dsm_parse_byte(uint32_t frame_time_ms, uint8_t b, uint16
|
||||
if ((frame_time_ms - last_rx_time_ms) >= 5) {
|
||||
dsm_decode_state = DSM_DECODE_STATE_SYNC;
|
||||
byte_input.ofs = 0;
|
||||
chan_count = 0;
|
||||
byte_input.buf[byte_input.ofs++] = b;
|
||||
}
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user