mirror of https://github.com/ArduPilot/ardupilot
AP_Math: added crc_sum_of_bytes_16()
This commit is contained in:
parent
bdab1054d6
commit
7102205be3
|
@ -599,13 +599,19 @@ uint8_t parity(uint8_t byte)
|
|||
return p;
|
||||
}
|
||||
|
||||
// sums the bytes in the supplied buffer, returns that sum mod 256
|
||||
// (i.e. shoved into a uint8_t)
|
||||
uint8_t crc_sum_of_bytes(uint8_t *data, uint16_t count)
|
||||
// sums the bytes in the supplied buffer, returns that sum mod 0xFFFF
|
||||
uint16_t crc_sum_of_bytes_16(const uint8_t *data, uint16_t count)
|
||||
{
|
||||
uint8_t ret = 0;
|
||||
uint16_t ret = 0;
|
||||
for (uint32_t i=0; i<count; i++) {
|
||||
ret += data[i];
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
// sums the bytes in the supplied buffer, returns that sum mod 256
|
||||
// (i.e. shoved into a uint8_t)
|
||||
uint8_t crc_sum_of_bytes(const uint8_t *data, uint16_t count)
|
||||
{
|
||||
return crc_sum_of_bytes_16(data, count) & 0xFF;
|
||||
}
|
||||
|
|
|
@ -66,4 +66,7 @@ uint8_t parity(uint8_t byte);
|
|||
|
||||
// sums the bytes in the supplied buffer, returns that sum mod 256
|
||||
// (i.e. shoved into a uint8_t)
|
||||
uint8_t crc_sum_of_bytes(uint8_t *data, uint16_t count);
|
||||
uint8_t crc_sum_of_bytes(const uint8_t *data, uint16_t count);
|
||||
|
||||
// sums the bytes in the supplied buffer, returns that sum mod 0xFFFF
|
||||
uint16_t crc_sum_of_bytes_16(const uint8_t *data, uint16_t count);
|
||||
|
|
Loading…
Reference in New Issue