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"
This commit is contained in:
Peter Barker 2023-11-29 13:02:03 +11:00 committed by Peter Barker
parent d34e6049c9
commit 4ede307be2
2 changed files with 4 additions and 4 deletions

View File

@ -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 @@ reset:
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

View File

@ -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 @@ reset:
// 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