Skip to content

Commit

Permalink
AP_Logger: add support to w25n02kv
Browse files Browse the repository at this point in the history
  • Loading branch information
tangpipi committed Apr 27, 2024
1 parent 338f492 commit dbaeaa5
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 3 deletions.
16 changes: 13 additions & 3 deletions libraries/AP_Logger/AP_Logger_W25N01GV.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
{
Expand Down Expand Up @@ -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:
Expand All @@ -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;
Expand Down Expand Up @@ -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;

Expand Down Expand Up @@ -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);
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Logger/AP_Logger_W25N01GV.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ class AP_Logger_W25N01GV : public AP_Logger_Block {
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev;
AP_HAL::Semaphore *dev_sem;

uint32_t flash_blockNum;

bool flash_died;
uint32_t erase_start_ms;
uint16_t erase_block;
Expand Down

0 comments on commit dbaeaa5

Please sign in to comment.