Skip to content

Instantly share code, notes, and snippets.

View tridge's full-sized avatar

Andrew Tridgell tridge

View GitHub Profile
@tridge
tridge / gist:5d52813cdd0c14ea389fea576852b2d3
Created December 13, 2022 23:30
ArduPilot lua differences from lua 5.4.4
diff -urN lua/lauxlib.c APM/libraries/AP_Scripting/lua/src/lauxlib.c
--- lua/lauxlib.c 2022-12-14 08:41:37.443587208 +1100
+++ APM/libraries/AP_Scripting/lua/src/lauxlib.c 2022-12-14 10:11:20.343728284 +1100
@@ -32,7 +32,6 @@
#define MAX_SIZET ((size_t)(~(size_t)0))
#endif
-
/*
** {======================================================
/*
create a thread that checks for ECC errors in flash. We disable
fault IRQs in the thread and monitor it from the main thread. If it
doesn't complete in 1s then erase flash This is the only way I've
found to check for ECC errors without causing a bus fault or
unconditionally erasing flash
*/
struct ecccheck {
const uint32_t *start;
uint32_t size;
/*
create a thread that checks for ECC errors in flash. We disable
fault IRQs in the thread and monitor it from the main thread. If it
doesn't complete in 1s then erase flash This is the only way I've
found to check for ECC errors without causing a bus fault or
unconditionally erasing flash
*/
struct ecccheck {
const uint32_t *start;
uint32_t size;
/*
create a thread that checks for ECC errors in flash. We disable
fault IRQs in the thread and monitor it from the main thread. If it
doesn't complete in 1s then erase flash This is the only way I've
found to check for ECC errors without causing a bus fault or
unconditionally erasing flash
*/
struct ecccheck {
const uint32_t *start;
uint32_t size;
void check_ecc_errors(void)
{
auto *dma = dmaStreamAlloc(STM32_DMA_STREAM_ID(1, 1), 0, nullptr, nullptr);
uint32_t buf[32];
uint32_t ofs = 0;
while (ofs < BOARD_FLASH_SIZE*1024 && FLASH->SR1 == 0 && FLASH->SR2 == 0) {
__disable_fault_irq();
dmaStartMemCopy(dma,
STM32_DMA_CR_PL(0) | STM32_DMA_CR_PSIZE_BYTE |
STM32_DMA_CR_MSIZE_BYTE,