From d9b6c6e0c9efed26e93cc81f55014684720292f4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 14 Jan 2019 12:05:29 +1100 Subject: [PATCH] AP_RCProtocol: on DSM sync error don't reset channel count this fixes the issue noticed by Andreyl in 3.6.5rc1 --- libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp index b0721a8ecf..bda3451190 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_DSM.cpp @@ -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;