From 3b9c9497aaa5171d8d7259b9abfa5bc91d197010 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 19 Feb 2024 13:07:54 +1100 Subject: [PATCH] AP_RCProtocol: correct CSRF->CRSF Co-authored-by: Andy Piper Co-authored-by: Andrew Tridgell --- libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp | 14 +++++++------- libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h | 4 ++-- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp index 2fd5a35a54..391f125eb8 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp @@ -150,7 +150,7 @@ static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0) #define CRSF_INTER_FRAME_TIME_US_250HZ 4000U // At fastest, frames are sent by the transmitter every 4 ms, 250 Hz #define CRSF_INTER_FRAME_TIME_US_150HZ 6667U // At medium, frames are sent by the transmitter every 6.667 ms, 150 Hz #define CRSF_INTER_FRAME_TIME_US_50HZ 20000U // At slowest, frames are sent by the transmitter every 20ms, 50 Hz -#define CSRF_HEADER_TYPE_LEN (CSRF_HEADER_LEN + 1) // header length including type +#define CRSF_HEADER_TYPE_LEN (CRSF_HEADER_LEN + 1) // header length including type #define CRSF_DIGITAL_CHANNEL_MIN 172 #define CRSF_DIGITAL_CHANNEL_MAX 1811 @@ -234,7 +234,7 @@ void AP_RCProtocol_CRSF::_process_byte(uint32_t timestamp_us, uint8_t byte) add_to_buffer(_frame_ofs++, byte); // need a header to get the length - if (_frame_ofs < CSRF_HEADER_TYPE_LEN) { + if (_frame_ofs < CRSF_HEADER_TYPE_LEN) { return; } @@ -243,7 +243,7 @@ void AP_RCProtocol_CRSF::_process_byte(uint32_t timestamp_us, uint8_t byte) } // parse the length - if (_frame_ofs == CSRF_HEADER_TYPE_LEN) { + if (_frame_ofs == CRSF_HEADER_TYPE_LEN) { _frame_crc = crc8_dvb_s2(0, _frame.type); // check for garbage frame if (_frame.length > CRSF_FRAME_PAYLOAD_MAX) { @@ -253,19 +253,19 @@ void AP_RCProtocol_CRSF::_process_byte(uint32_t timestamp_us, uint8_t byte) } // update crc - if (_frame_ofs < _frame.length + CSRF_HEADER_LEN) { + if (_frame_ofs < _frame.length + CRSF_HEADER_LEN) { _frame_crc = crc8_dvb_s2(_frame_crc, byte); } // overflow check - if (_frame_ofs > _frame.length + CSRF_HEADER_LEN) { + if (_frame_ofs > _frame.length + CRSF_HEADER_LEN) { _frame_ofs = 0; return; } // decode whatever we got and expect - if (_frame_ofs == _frame.length + CSRF_HEADER_LEN) { - log_data(AP_RCProtocol::CRSF, timestamp_us, (const uint8_t*)&_frame, _frame_ofs - CSRF_HEADER_LEN); + if (_frame_ofs == _frame.length + CRSF_HEADER_LEN) { + log_data(AP_RCProtocol::CRSF, timestamp_us, (const uint8_t*)&_frame, _frame_ofs - CRSF_HEADER_LEN); // we consumed the partial frame, reset _frame_ofs = 0; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h index c063175e01..3546ed484c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h @@ -29,8 +29,8 @@ #define CRSF_MAX_CHANNELS 24U // Maximum number of channels from crsf datastream #define CRSF_FRAMELEN_MAX 64U // maximum possible framelength -#define CSRF_HEADER_LEN 2U // header length -#define CRSF_FRAME_PAYLOAD_MAX (CRSF_FRAMELEN_MAX - CSRF_HEADER_LEN) // maximum size of the frame length field in a packet +#define CRSF_HEADER_LEN 2U // header length +#define CRSF_FRAME_PAYLOAD_MAX (CRSF_FRAMELEN_MAX - CRSF_HEADER_LEN) // maximum size of the frame length field in a packet #define CRSF_BAUDRATE 416666U #define ELRS_BAUDRATE 420000U #define CRSF_TX_TIMEOUT 500000U // the period after which the transmitter is considered disconnected (matches copters failsafe)