mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_Logger: add performance debug to W25NXX logger
This commit is contained in:
parent
5f8e339d47
commit
6ac4bf3fc4
@ -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
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user