From 9a93a5719356ad676028c363718824cabf14aac4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 13:02:03 +1100 Subject: [PATCH] AP_RCProtocol: rename crc_sum8 to crc_sum8_with_carry the name "sum8" is usually used for "sum all bytes into a uint8_t discarding carry" --- libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp | 4 ++-- libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp index 08bc5a06fa791..c16e2c2b4592a 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp @@ -179,7 +179,7 @@ void AP_RCProtocol_FPort::decode_downlink(const FPort_Frame &frame) buf[3] = telem_data.packet.appid & 0xFF; buf[4] = telem_data.packet.appid >> 8; memcpy(&buf[5], &telem_data.packet.data, 4); - buf[9] = crc_sum8(&buf[0], 9); + buf[9] = crc_sum8_with_carry(&buf[0], 9); // perform byte stuffing per FPort spec uint8_t len = 0; @@ -307,7 +307,7 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b) bool AP_RCProtocol_FPort::check_checksum(void) { const uint8_t len = byte_input.buf[1]+2; - return crc_sum8(&byte_input.buf[1], len) == 0x00; + return crc_sum8_with_carry(&byte_input.buf[1], len) == 0x00; } // support byte input diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp index dc9eceb61f8dd..2631f51d03025 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp @@ -179,7 +179,7 @@ void AP_RCProtocol_FPort2::decode_downlink(const FPort2_Frame &frame) // get fresh telem_data in the next call telem_data.available = false; } - buf[9] = crc_sum8(&buf[1], 8); + buf[9] = crc_sum8_with_carry(&buf[1], 8); uart->write(buf, sizeof(buf)); #endif @@ -286,7 +286,7 @@ void AP_RCProtocol_FPort2::_process_byte(uint32_t timestamp_us, uint8_t b) // check checksum byte bool AP_RCProtocol_FPort2::check_checksum(void) { - return crc_sum8(&byte_input.buf[1], byte_input.control_len-1) == 0; + return crc_sum8_with_carry(&byte_input.buf[1], byte_input.control_len-1) == 0; } // support byte input