From 0dac7d5cfea4d7774f9b662f08b078faae428c6e Mon Sep 17 00:00:00 2001 From: tanghongkai Date: Wed, 24 Apr 2024 23:23:38 +0800 Subject: [PATCH] AP_Logger: add support to w25n02kv --- libraries/AP_Logger/AP_Logger_W25N01GV.cpp | 16 +++++++++++++--- libraries/AP_Logger/AP_Logger_W25N01GV.h | 2 ++ 2 files changed, 15 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.cpp b/libraries/AP_Logger/AP_Logger_W25N01GV.cpp index 86ce642c99..09454a5ee1 100644 --- a/libraries/AP_Logger/AP_Logger_W25N01GV.cpp +++ b/libraries/AP_Logger/AP_Logger_W25N01GV.cpp @@ -52,9 +52,12 @@ extern const AP_HAL::HAL& hal; #define W25N01G_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us #define W25N01G_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms #define W25N01G_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms + #define W25N01G_NUM_BLOCKS 1024 +#define W25N02K_NUM_BLOCKS 2048 #define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21 +#define JEDEC_ID_WINBOND_W25N02KV 0xEFAA22 void AP_Logger_W25N01GV::Init() { @@ -133,6 +136,13 @@ bool AP_Logger_W25N01GV::getSectorCount(void) df_PageSize = 2048; df_PagePerBlock = 64; df_PagePerSector = 64; // make sectors equivalent to block + flash_blockNum = W25N01G_NUM_BLOCKS; + break; + case JEDEC_ID_WINBOND_W25N02KV: + df_PageSize = 2048; + df_PagePerBlock = 64; + df_PagePerSector = 64; // make sectors equivalent to block + flash_blockNum = W25N02K_NUM_BLOCKS; break; default: @@ -141,7 +151,7 @@ bool AP_Logger_W25N01GV::getSectorCount(void) return false; } - df_NumPages = W25N01G_NUM_BLOCKS * df_PagePerBlock; + df_NumPages = flash_blockNum * df_PagePerBlock; printf("SPI Flash 0x%08x found pages=%u\n", id, df_NumPages); return true; @@ -186,7 +196,7 @@ void AP_Logger_W25N01GV::send_command_addr(uint8_t command, uint32_t PageAdr) { uint8_t cmd[4]; cmd[0] = command; - cmd[1] = 0; // dummy + cmd[1] = (PageAdr >> 16) & 0xff; cmd[2] = (PageAdr >> 8) & 0xff; cmd[3] = (PageAdr >> 0) & 0xff; @@ -312,7 +322,7 @@ void AP_Logger_W25N01GV::StartErase() bool AP_Logger_W25N01GV::InErase() { if (erase_start_ms && !Busy()) { - if (erase_block < W25N01G_NUM_BLOCKS) { + if (erase_block < flash_blockNum) { SectorErase(erase_block++); } else { printf("Dataflash: erase done (%u ms)\n", AP_HAL::millis() - erase_start_ms); diff --git a/libraries/AP_Logger/AP_Logger_W25N01GV.h b/libraries/AP_Logger/AP_Logger_W25N01GV.h index 556603eaff..276eb43b8c 100644 --- a/libraries/AP_Logger/AP_Logger_W25N01GV.h +++ b/libraries/AP_Logger/AP_Logger_W25N01GV.h @@ -39,6 +39,8 @@ private: AP_HAL::OwnPtr dev; AP_HAL::Semaphore *dev_sem; + uint32_t flash_blockNum; + bool flash_died; uint32_t erase_start_ms; uint16_t erase_block;