mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: added crc_sum8
for FPort/FPort2
This commit is contained in:
parent
66596dcf25
commit
747b48d0a8
@ -334,3 +334,16 @@ uint32_t crc_crc24(const uint8_t *bytes, uint16_t len)
|
||||
}
|
||||
return crc;
|
||||
}
|
||||
|
||||
// simple 8 bit checksum used by FPort
|
||||
uint8_t crc_sum8(const uint8_t *p, uint8_t len)
|
||||
{
|
||||
uint16_t sum = 0;
|
||||
for (uint8_t i=0; i<len; i++) {
|
||||
sum += p[i];
|
||||
sum += sum >> 8;
|
||||
sum &= 0xFF;
|
||||
}
|
||||
sum = 0xff - ((sum & 0xff) + (sum >> 8));
|
||||
return sum;
|
||||
}
|
||||
|
@ -28,6 +28,9 @@ uint32_t crc_crc32(uint32_t crc, const uint8_t *buf, uint32_t size);
|
||||
uint32_t crc32_small(uint32_t crc, const uint8_t *buf, uint32_t size);
|
||||
uint32_t crc_crc24(const uint8_t *bytes, uint16_t len);
|
||||
|
||||
// checksum used by SPORT/FPort
|
||||
uint8_t crc_sum8(const uint8_t *p, uint8_t len);
|
||||
|
||||
// Copyright (C) 2010 Swift Navigation Inc.
|
||||
// Contact: Fergus Noble <fergus@swift-nav.com>
|
||||
uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc);
|
||||
|
Loading…
Reference in New Issue
Block a user