Skip to content

Commit

Permalink
HAL_ChibiOS: fixed a cache corruption issue on H7
Browse files Browse the repository at this point in the history
This fixes a bug introduced in this PR:

#25900

the bug is that when we don't go via the bouncebuffer on H7 we were
also skipping the cache invalidate/flush ops. This caused data
corruption for filesystem operations, particularly noticible as lua
scripts failing to load with parse errors or log corruption
  • Loading branch information
tridge committed Mar 16, 2024
1 parent 562da16 commit e983738
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 3 deletions.
15 changes: 13 additions & 2 deletions libraries/AP_HAL_ChibiOS/hwdef/common/bouncebuffer.c
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,13 @@ void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_b
bool bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf, uint32_t size)
{
if (!bouncebuffer || mem_is_dma_safe(*buf, size, bouncebuffer->on_axi_sram)) {
// nothing needs to be done
#if defined(STM32H7)
/*
on H7 the cache needs invalidating before a read to ensure
there is no stale data in the buffer
*/
stm32_cacheBufferInvalidate(*buf, (size+31)&~31);
#endif
return true;
}
osalDbgAssert((bouncebuffer->busy == false), "bouncebuffer read");
Expand Down Expand Up @@ -97,7 +103,12 @@ void bouncebuffer_finish_read(struct bouncebuffer_t *bouncebuffer, const uint8_t
bool bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t **buf, uint32_t size)
{
if (!bouncebuffer || mem_is_dma_safe(*buf, size, bouncebuffer->on_axi_sram)) {
// nothing needs to be done
#if defined(STM32H7)
/*
on H7 we need to flush any pending writes to memory before the DMA operation
*/
stm32_cacheBufferFlush(*buf, (size+31)&~31);
#endif
return true;
}
osalDbgAssert((bouncebuffer->busy == false), "bouncebuffer write");
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c
Original file line number Diff line number Diff line change
Expand Up @@ -635,7 +635,7 @@ bool mem_is_dma_safe(const void *addr, uint32_t size, bool filesystem_op)
// use bouncebuffer for all non FS ops on H7
return false;
}
if (((uint32_t)addr) & 0x1F) {
if ((((uint32_t)addr) & 0x1F) != 0 || (size & 0x1F) != 0) {
return false;
}
if (filesystem_op) {
Expand Down

0 comments on commit e983738

Please sign in to comment.