Skip to content

Commit

Permalink
AP_Math: rename crc_sum8 to crc_sum8_with_carry
Browse files Browse the repository at this point in the history
the name "sum8" is usually used for "sum all bytes into a uint8_t discarding carry"
  • Loading branch information
peterbarker committed Nov 29, 2023
1 parent 7da434d commit 34ecdec
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 3 deletions.
2 changes: 1 addition & 1 deletion libraries/AP_Math/crc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -481,7 +481,7 @@ uint32_t crc_crc24(const uint8_t *bytes, uint16_t len)
}

// simple 8 bit checksum used by FPort
uint8_t crc_sum8(const uint8_t *p, uint8_t len)
uint8_t crc_sum8_with_carry(const uint8_t *p, uint8_t len)
{
uint16_t sum = 0;
for (uint8_t i=0; i<len; i++) {
Expand Down
6 changes: 4 additions & 2 deletions libraries/AP_Math/crc.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,10 @@ 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);
uint16_t crc_crc16_ibm(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size);

// checksum used by SPORT/FPort
uint8_t crc_sum8(const uint8_t *p, uint8_t len);
// checksum used by SPORT/FPort. For each byte, adds it to a 16-bit
// sum, then adds those two bytes together. Returns the complement of
// the final sum.
uint8_t crc_sum8_with_carry(const uint8_t *p, uint8_t len);

// Copyright (C) 2010 Swift Navigation Inc.
// Contact: Fergus Noble <[email protected]>
Expand Down

0 comments on commit 34ecdec

Please sign in to comment.