mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: use crc32_small()
This commit is contained in:
parent
1ec921560e
commit
31f7a62cdc
|
@ -41,6 +41,7 @@
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
#include <AP_Math/crc.h>
|
||||||
#include "ch.h"
|
#include "ch.h"
|
||||||
#include "hal.h"
|
#include "hal.h"
|
||||||
#include "hwdef.h"
|
#include "hwdef.h"
|
||||||
|
@ -319,38 +320,6 @@ cout_word(uint32_t val)
|
||||||
cout((uint8_t *)&val, 4);
|
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
|
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
|
ensure that we only ever do 32 byte aligned writes on STM32H7. If
|
||||||
|
@ -732,7 +701,7 @@ bootloader(unsigned timeout)
|
||||||
} else {
|
} else {
|
||||||
bytes = flash_func_read_word(p);
|
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);
|
cout_word(sum);
|
||||||
|
|
Loading…
Reference in New Issue