From 696d4b47a18577681778bc28f93c0bbdd95a5f1a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 5 Nov 2018 14:56:16 +1100 Subject: [PATCH] AP_RCProtocol: use SoftSerial clock for SRXL --- libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp | 11 ++++++----- libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h | 3 +-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp index 1d6260d177..49f6c297df 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp @@ -51,10 +51,8 @@ void AP_RCProtocol_SRXL::process_pulse(uint32_t width_s0, uint32_t width_s1) { uint8_t b; if (ss.process_pulse(width_s0, width_s1, b)) { - _process_byte(clock_us, b, 115200); + _process_byte(ss.get_byte_timestamp_us(), b); } - // keep a clock based on the pulses - clock_us += (width_s0 + width_s1); } @@ -195,7 +193,7 @@ int AP_RCProtocol_SRXL::srxl_channels_get_v5(uint16_t max_values, uint8_t *num_v return 0; } -void AP_RCProtocol_SRXL::_process_byte(uint32_t timestamp_us, uint8_t byte, uint32_t baudrate) +void AP_RCProtocol_SRXL::_process_byte(uint32_t timestamp_us, uint8_t byte) { /*----------------------------------------distinguish different srxl variants at the beginning of each frame---------------------------------------------- */ /* Check if we have a new begin of a frame --> indicators: Time gap in datastream + SRXL header 0xA*/ @@ -296,5 +294,8 @@ void AP_RCProtocol_SRXL::_process_byte(uint32_t timestamp_us, uint8_t byte, uint */ void AP_RCProtocol_SRXL::process_byte(uint8_t byte, uint32_t baudrate) { - _process_byte(AP_HAL::micros(), byte, baudrate); + if (baudrate != 115200) { + return; + } + _process_byte(AP_HAL::micros(), byte); } diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h index fb4119f604..0bb88a16e6 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SRXL.h @@ -42,7 +42,7 @@ public: void process_pulse(uint32_t width_s0, uint32_t width_s1) override; void process_byte(uint8_t byte, uint32_t baudrate) override; private: - void _process_byte(uint32_t timestamp_us, uint8_t byte, uint32_t baudrate); + void _process_byte(uint32_t timestamp_us, uint8_t byte); static uint16_t srxl_crc16(uint16_t crc, uint8_t new_byte); int srxl_channels_get_v1v2(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state); int srxl_channels_get_v5(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state); @@ -62,7 +62,6 @@ private: uint8_t decode_state_next = STATE_IDLE; /* State of frame decoding thatwill be applied when the next byte from dataframe drops in */ 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 */ SoftSerial ss{115200, SoftSerial::SERIAL_CONFIG_8N1}; };