mirror of https://github.com/ArduPilot/ardupilot
AP_Math: add crc_sum_of_bytes
sums the values of the bytes in a buffer and returns that sum modulus 256
This commit is contained in:
parent
32f6c1c53f
commit
3f730a8a94
|
@ -598,3 +598,14 @@ 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)
|
||||
{
|
||||
uint8_t ret = 0;
|
||||
for (uint32_t i=0; i<count; i++) {
|
||||
ret += data[i];
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -61,3 +61,7 @@ uint64_t crc_crc64(const uint32_t *data, uint16_t num_words);
|
|||
// return the parity of byte - "1" if there is an odd number of bits
|
||||
// set, "0" if there is an even number of bits set
|
||||
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);
|
||||
|
|
Loading…
Reference in New Issue