mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
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:
parent
d34e6049c9
commit
4ede307be2
@ -179,7 +179,7 @@ void AP_RCProtocol_FPort::decode_downlink(const FPort_Frame &frame)
|
|||||||
buf[3] = telem_data.packet.appid & 0xFF;
|
buf[3] = telem_data.packet.appid & 0xFF;
|
||||||
buf[4] = telem_data.packet.appid >> 8;
|
buf[4] = telem_data.packet.appid >> 8;
|
||||||
memcpy(&buf[5], &telem_data.packet.data, 4);
|
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
|
// perform byte stuffing per FPort spec
|
||||||
uint8_t len = 0;
|
uint8_t len = 0;
|
||||||
@ -307,7 +307,7 @@ reset:
|
|||||||
bool AP_RCProtocol_FPort::check_checksum(void)
|
bool AP_RCProtocol_FPort::check_checksum(void)
|
||||||
{
|
{
|
||||||
const uint8_t len = byte_input.buf[1]+2;
|
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
|
// support byte input
|
||||||
|
@ -179,7 +179,7 @@ void AP_RCProtocol_FPort2::decode_downlink(const FPort2_Frame &frame)
|
|||||||
// get fresh telem_data in the next call
|
// get fresh telem_data in the next call
|
||||||
telem_data.available = false;
|
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));
|
uart->write(buf, sizeof(buf));
|
||||||
#endif
|
#endif
|
||||||
@ -286,7 +286,7 @@ reset:
|
|||||||
// check checksum byte
|
// check checksum byte
|
||||||
bool AP_RCProtocol_FPort2::check_checksum(void)
|
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
|
// support byte input
|
||||||
|
Loading…
Reference in New Issue
Block a user