AP_RCProtocol: fixed DSM parser for 8 channels

this ensures we remember channels from the previous frame, avoiding a
bug with more than 7 channels
This commit is contained in:
Andrew Tridgell 2018-11-15 17:04:54 +11:00
parent a75d678e7f
commit da0301c208
2 changed files with 8 additions and 5 deletions

View File

@ -381,11 +381,9 @@ void AP_RCProtocol_DSM::_process_byte(uint32_t timestamp_us, uint8_t b)
byte_input.last_byte_us = timestamp_us;
byte_input.buf[byte_input.ofs++] = b;
if (byte_input.ofs == 16) {
uint16_t values[8];
uint16_t num_values=0;
if (dsm_decode(timestamp_us, byte_input.buf, values, &num_values, 8) &&
num_values >= MIN_RCIN_CHANNELS) {
add_input(num_values, values, false);
if (dsm_decode(timestamp_us, byte_input.buf, &last_values[0], &num_channels, AP_DSM_MAX_CHANNELS) &&
num_channels >= MIN_RCIN_CHANNELS) {
add_input(num_channels, last_values, false);
}
byte_input.ofs = 0;

View File

@ -20,6 +20,8 @@
#include "AP_RCProtocol.h"
#include "SoftSerial.h"
#define AP_DSM_MAX_CHANNELS 12
class AP_RCProtocol_DSM : public AP_RCProtocol_Backend {
public:
AP_RCProtocol_DSM(AP_RCProtocol &_frontend) : AP_RCProtocol_Backend(_frontend) {}
@ -59,6 +61,9 @@ private:
} bind_state;
uint32_t bind_last_ms;
uint16_t last_values[AP_DSM_MAX_CHANNELS];
uint16_t num_channels;
struct {
uint8_t buf[16];
uint8_t ofs;