diff --git a/Tools/AP_Bootloader/bl_protocol.cpp b/Tools/AP_Bootloader/bl_protocol.cpp index 7ce33dbdc2..1dae1c64ac 100644 --- a/Tools/AP_Bootloader/bl_protocol.cpp +++ b/Tools/AP_Bootloader/bl_protocol.cpp @@ -41,6 +41,7 @@ #include #include +#include #include "ch.h" #include "hal.h" #include "hwdef.h" @@ -319,38 +320,6 @@ cout_word(uint32_t val) cout((uint8_t *)&val, 4); } -static uint32_t -crc32(const uint8_t *src, unsigned len, unsigned state) -{ - static uint32_t crctab[256]; - - /* check whether we have generated the CRC table yet */ - /* this is much smaller than a static table */ - if (crctab[1] == 0) { - for (unsigned i = 0; i < 256; i++) { - uint32_t c = i; - - for (unsigned j = 0; j < 8; j++) { - if (c & 1) { - c = 0xedb88320U ^ (c >> 1); - - } else { - c = c >> 1; - } - } - - crctab[i] = c; - } - } - - for (unsigned i = 0; i < len; i++) { - state = crctab[(state ^ src[i]) & 0xff] ^ (state >> 8); - } - - return state; -} - - /* we use a write buffer for flashing, both for efficiency and to ensure that we only ever do 32 byte aligned writes on STM32H7. If @@ -732,7 +701,7 @@ bootloader(unsigned timeout) } else { bytes = flash_func_read_word(p); } - sum = crc32((uint8_t *)&bytes, sizeof(bytes), sum); + sum = crc32_small(sum, (uint8_t *)&bytes, sizeof(bytes)); } cout_word(sum);