Browse Source

AP_Math: added CRCs needed by AP_MSP

zr-v5.1
yaapu 5 years ago committed by Andrew Tridgell
parent
commit
144f7df02f
  1. 12
      libraries/AP_Math/crc.cpp
  2. 1
      libraries/AP_Math/crc.h

12
libraries/AP_Math/crc.cpp

@ -110,6 +110,18 @@ uint8_t crc8_dvb(uint8_t crc, uint8_t a, uint8_t seed) @@ -110,6 +110,18 @@ uint8_t crc8_dvb(uint8_t crc, uint8_t a, uint8_t seed)
return crc;
}
// crc8 from betaflight
uint8_t crc8_dvb_s2_update(uint8_t crc, const void *data, uint32_t length)
{
const uint8_t *p = (const uint8_t *)data;
const uint8_t *pend = p + length;
for (; p != pend; p++) {
crc = crc8_dvb_s2(crc, *p);
}
return crc;
}
/*
xmodem CRC thanks to avr-liberty
https://github.com/dreamiurg/avr-liberty

1
libraries/AP_Math/crc.h

@ -21,6 +21,7 @@ uint16_t crc_crc4(uint16_t *data); @@ -21,6 +21,7 @@ uint16_t crc_crc4(uint16_t *data);
uint8_t crc_crc8(const uint8_t *p, uint8_t len);
uint8_t crc8_dvb_s2(uint8_t crc, uint8_t a);
uint8_t crc8_dvb(uint8_t crc, uint8_t a, uint8_t seed);
uint8_t crc8_dvb_s2_update(uint8_t crc, const void *data, uint32_t length);
uint16_t crc_xmodem_update(uint16_t crc, uint8_t data);
uint16_t crc_xmodem(const uint8_t *data, uint16_t len);
uint32_t crc_crc32(uint32_t crc, const uint8_t *buf, uint32_t size);

Loading…
Cancel
Save