mirror of https://github.com/ArduPilot/ardupilot
AP_Math: Add fletcher16 CRC
This commit is contained in:
parent
584a1f8c49
commit
32fd21592a
|
@ -387,7 +387,7 @@ uint16_t crc16_ccitt_GDL90(const uint8_t *buf, uint32_t len, uint16_t crc)
|
|||
* @param [in] len size of buffer
|
||||
* @return CRC value
|
||||
*/
|
||||
uint16_t calc_crc_modbus(uint8_t *buf, uint16_t len)
|
||||
uint16_t calc_crc_modbus(const uint8_t *buf, uint16_t len)
|
||||
{
|
||||
uint16_t crc = 0xFFFF;
|
||||
for (uint16_t pos = 0; pos < len; pos++) {
|
||||
|
@ -405,6 +405,18 @@ uint16_t calc_crc_modbus(uint8_t *buf, uint16_t len)
|
|||
return crc;
|
||||
}
|
||||
|
||||
// fletcher 16 implementation
|
||||
uint16_t crc_fletcher16(const uint8_t *buffer, uint32_t len) {
|
||||
uint16_t c0 = 0;
|
||||
uint16_t c1 = 0;
|
||||
for (uint32_t i = 0; i < len; i++) {
|
||||
c0 = (c0 + buffer[i]) % 255;
|
||||
c1 = (c1 + c0) % 255;
|
||||
}
|
||||
|
||||
return (c1 << 8) | c0;
|
||||
}
|
||||
|
||||
// FNV-1a implementation
|
||||
#define FNV_1_PRIME_64 1099511628211UL
|
||||
void hash_fnv_1a(uint32_t len, const uint8_t* buf, uint64_t* hash)
|
||||
|
|
|
@ -45,7 +45,9 @@ uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc);
|
|||
// https://www.faa.gov/nextgen/programs/adsb/archival/media/gdl90_public_icd_reva.pdf
|
||||
uint16_t crc16_ccitt_GDL90(const uint8_t *buf, uint32_t len, uint16_t crc);
|
||||
|
||||
uint16_t calc_crc_modbus(uint8_t *buf, uint16_t len);
|
||||
uint16_t calc_crc_modbus(const uint8_t *buf, uint16_t len);
|
||||
|
||||
uint16_t crc_fletcher16(const uint8_t * buffer, uint32_t len);
|
||||
|
||||
// generate 64bit FNV1a hash from buffer
|
||||
#define FNV_1_OFFSET_BASIS_64 14695981039346656037UL
|
||||
|
|
Loading…
Reference in New Issue