From b93dee7fe6e4a96ba8be38af97a4a4d764551b43 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 5 Nov 2018 13:02:22 +1100 Subject: [PATCH] AP_RCProtocol: switched SRXL to SoftSerial decoder --- .../AP_RCProtocol/AP_RCProtocol_SRXL.cpp | 65 ++----------------- libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h | 7 +- 2 files changed, 7 insertions(+), 65 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp index e3b366993e..1d6260d177 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp @@ -49,69 +49,12 @@ uint16_t AP_RCProtocol_SRXL::srxl_crc16(uint16_t crc, uint8_t new_byte) void AP_RCProtocol_SRXL::process_pulse(uint32_t width_s0, uint32_t width_s1) { - // convert to bit widths, allowing for up to about 4usec error, assuming 115200 bps - uint16_t bits_s0 = ((width_s0+4)*(uint32_t)115200) / 1000000; - uint16_t bits_s1 = ((width_s1+4)*(uint32_t)115200) / 1000000; - uint8_t bit_ofs, byte_ofs; - uint16_t nbits; - + uint8_t b; + if (ss.process_pulse(width_s0, width_s1, b)) { + _process_byte(clock_us, b, 115200); + } // keep a clock based on the pulses clock_us += (width_s0 + width_s1); - - if (bits_s0 == 0 || bits_s1 == 0) { - // invalid data - goto reset; - } - - byte_ofs = srxl_state.bit_ofs/10; - bit_ofs = srxl_state.bit_ofs%10; - if (byte_ofs >= SRXL_FRAMELEN_MAX) { - goto reset; - } - // pull in the high bits - nbits = bits_s0; - if (nbits+bit_ofs > 10) { - nbits = 10 - bit_ofs; - } - srxl_state.bytes[byte_ofs] |= ((1U< 10) { - // we have a full frame - uint8_t byte; - uint8_t i; - for (i=0; i <= byte_ofs; i++) { - // get raw data - uint16_t v = srxl_state.bytes[i]; - - // check start bit - if ((v & 1) != 0) { - break; - } - // check stop bits - if ((v & 0x200) != 0x200) { - break; - } - byte = ((v>>1) & 0xFF); - _process_byte(clock_us, byte, 115200); - } - memset(&srxl_state, 0, sizeof(srxl_state)); - } - - byte_ofs = srxl_state.bit_ofs/10; - bit_ofs = srxl_state.bit_ofs%10; - - if (bits_s1+bit_ofs > 10) { - // invalid data - goto reset; - } - - // pull in the low bits - srxl_state.bit_ofs += bits_s1; - - return; -reset: - memset(&srxl_state, 0, sizeof(srxl_state)); } diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h index f48c0ba076..fb4119f604 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h @@ -18,6 +18,7 @@ #pragma once #include "AP_RCProtocol.h" +#include "SoftSerial.h" #define SRXL_MIN_FRAMESPACE_US 8000U /* Minumum space between srxl frames in us (applies to all variants) */ #define SRXL_MAX_CHANNELS 20U /* Maximum number of channels from srxl datastream */ @@ -62,8 +63,6 @@ private: uint16_t crc_fmu = 0U; /* CRC calculated over payload from srxl datastream on this machine */ uint16_t crc_receiver = 0U; /* CRC extracted from srxl datastream */ uint32_t clock_us; /* clock calculated from pulse lengths */ - struct { - uint16_t bytes[SRXL_FRAMELEN_MAX]; - uint16_t bit_ofs; - } srxl_state; + + SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1}; };