AP_Logger: add performance debug to W25NXX logger

This commit is contained in:
Andy Piper 2024-12-07 19:59:58 +00:00 committed by Andrew Tridgell
parent 5f8e339d47
commit 6ac4bf3fc4

View File

@ -247,6 +247,11 @@ void AP_Logger_W25NXX::PageToBuffer(uint32_t pageNum)
}
}
//#define AP_W25NXX_DEBUG
#ifdef AP_W25NXX_DEBUG
static uint32_t block_writes;
static uint32_t last_write_msg_ms;
#endif
void AP_Logger_W25NXX::BufferToPage(uint32_t pageNum)
{
if (pageNum == 0 || pageNum > df_NumPages+1) {
@ -283,6 +288,15 @@ void AP_Logger_W25NXX::BufferToPage(uint32_t pageNum)
WITH_SEMAPHORE(dev_sem);
send_command_addr(JEDEC_PROGRAM_EXECUTE, PageAdr);
}
#ifdef AP_W25NXX_DEBUG
block_writes++;
if (AP_HAL::millis() - last_write_msg_ms > 5000) {
hal.console->printf("W25NXX: writes %lukB/s, pages %lu/s\n", (block_writes*df_PageSize)/(5*1024), block_writes/5);
block_writes = 0;
last_write_msg_ms = AP_HAL::millis();
}
#endif
}
/*