Skip to content

Commit

Permalink
AP_Logger: cope with rename of AP_Logger_JEDEC driver
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Feb 26, 2024
1 parent 93041e1 commit da7198c
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 20 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_Logger/AP_Logger.cpp
Expand Up @@ -5,7 +5,7 @@
#include "AP_Logger_Backend.h"

#include "AP_Logger_File.h"
#include "AP_Logger_DataFlash.h"
#include "AP_Logger_JEDEC.h"
#include "AP_Logger_W25N01GV.h"
#include "AP_Logger_MAVLink.h"

Expand Down Expand Up @@ -36,7 +36,7 @@ extern const AP_HAL::HAL& hal;
#endif

#ifndef HAL_LOGGING_DATAFLASH_DRIVER
#define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_DataFlash
#define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_JEDEC
#endif

#ifndef HAL_LOGGING_STACK_SIZE
Expand Down
30 changes: 15 additions & 15 deletions libraries/AP_Logger/AP_Logger_JEDEC.cpp
Expand Up @@ -8,7 +8,7 @@

#include <AP_HAL/AP_HAL.h>

#include "AP_Logger_DataFlash.h"
#include "AP_Logger_JEDEC.h"

#include <stdio.h>

Expand Down Expand Up @@ -57,7 +57,7 @@ extern const AP_HAL::HAL& hal;
#define JEDEC_ID_WINBOND_W25Q128_2 0xEF7018
#define JEDEC_ID_CYPRESS_S25FL128L 0x016018

void AP_Logger_DataFlash::Init()
void AP_Logger_JEDEC::Init()
{
dev = hal.spi->get_device("dataflash");
if (!dev) {
Expand Down Expand Up @@ -86,7 +86,7 @@ void AP_Logger_DataFlash::Init()
/*
wait for busy flag to be cleared
*/
void AP_Logger_DataFlash::WaitReady()
void AP_Logger_JEDEC::WaitReady()
{
if (flash_died) {
return;
Expand All @@ -103,7 +103,7 @@ void AP_Logger_DataFlash::WaitReady()
}
}

bool AP_Logger_DataFlash::getSectorCount(void)
bool AP_Logger_JEDEC::getSectorCount(void)
{
WaitReady();

Expand Down Expand Up @@ -171,7 +171,7 @@ bool AP_Logger_DataFlash::getSectorCount(void)
}

// Read the status register
uint8_t AP_Logger_DataFlash::ReadStatusReg()
uint8_t AP_Logger_JEDEC::ReadStatusReg()
{
WITH_SEMAPHORE(dev_sem);
uint8_t cmd = JEDEC_READ_STATUS;
Expand All @@ -180,12 +180,12 @@ uint8_t AP_Logger_DataFlash::ReadStatusReg()
return status;
}

bool AP_Logger_DataFlash::Busy()
bool AP_Logger_JEDEC::Busy()
{
return (ReadStatusReg() & (JEDEC_STATUS_BUSY | JEDEC_STATUS_SRP0)) != 0;
}

void AP_Logger_DataFlash::Enter4ByteAddressMode(void)
void AP_Logger_JEDEC::Enter4ByteAddressMode(void)
{
WITH_SEMAPHORE(dev_sem);

Expand All @@ -196,7 +196,7 @@ void AP_Logger_DataFlash::Enter4ByteAddressMode(void)
/*
send a command with an address
*/
void AP_Logger_DataFlash::send_command_addr(uint8_t command, uint32_t PageAdr)
void AP_Logger_JEDEC::send_command_addr(uint8_t command, uint32_t PageAdr)
{
uint8_t cmd[5];
cmd[0] = command;
Expand All @@ -215,7 +215,7 @@ void AP_Logger_DataFlash::send_command_addr(uint8_t command, uint32_t PageAdr)
}


void AP_Logger_DataFlash::PageToBuffer(uint32_t pageNum)
void AP_Logger_JEDEC::PageToBuffer(uint32_t pageNum)
{
if (pageNum == 0 || pageNum > df_NumPages+1) {
printf("Invalid page read %u\n", pageNum);
Expand Down Expand Up @@ -244,7 +244,7 @@ void AP_Logger_DataFlash::PageToBuffer(uint32_t pageNum)
read_cache_valid = true;
}

void AP_Logger_DataFlash::BufferToPage(uint32_t pageNum)
void AP_Logger_JEDEC::BufferToPage(uint32_t pageNum)
{
if (pageNum == 0 || pageNum > df_NumPages+1) {
printf("Invalid page write %u\n", pageNum);
Expand All @@ -271,7 +271,7 @@ void AP_Logger_DataFlash::BufferToPage(uint32_t pageNum)
/*
erase one sector (sizes varies with hw)
*/
void AP_Logger_DataFlash::SectorErase(uint32_t blockNum)
void AP_Logger_JEDEC::SectorErase(uint32_t blockNum)
{
WriteEnable();

Expand All @@ -284,7 +284,7 @@ void AP_Logger_DataFlash::SectorErase(uint32_t blockNum)
/*
erase one 4k sector
*/
void AP_Logger_DataFlash::Sector4kErase(uint32_t sectorNum)
void AP_Logger_JEDEC::Sector4kErase(uint32_t sectorNum)
{
WriteEnable();

Expand All @@ -293,7 +293,7 @@ void AP_Logger_DataFlash::Sector4kErase(uint32_t sectorNum)
send_command_addr(JEDEC_SECTOR4_ERASE, SectorAddr);
}

void AP_Logger_DataFlash::StartErase()
void AP_Logger_JEDEC::StartErase()
{
WriteEnable();

Expand All @@ -306,7 +306,7 @@ void AP_Logger_DataFlash::StartErase()
printf("Dataflash: erase started\n");
}

bool AP_Logger_DataFlash::InErase()
bool AP_Logger_JEDEC::InErase()
{
if (erase_start_ms && !Busy()) {
printf("Dataflash: erase done (%u ms)\n", AP_HAL::millis() - erase_start_ms);
Expand All @@ -315,7 +315,7 @@ bool AP_Logger_DataFlash::InErase()
return erase_start_ms != 0;
}

void AP_Logger_DataFlash::WriteEnable(void)
void AP_Logger_JEDEC::WriteEnable(void)
{
WaitReady();
WITH_SEMAPHORE(dev_sem);
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_Logger/AP_Logger_JEDEC.h
Expand Up @@ -9,13 +9,13 @@

#if HAL_LOGGING_DATAFLASH_ENABLED

class AP_Logger_DataFlash : public AP_Logger_Block {
class AP_Logger_JEDEC : public AP_Logger_Block {
public:
AP_Logger_DataFlash(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) :
AP_Logger_JEDEC(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) :
AP_Logger_Block(front, writer) {}
static AP_Logger_Backend *probe(AP_Logger &front,
LoggerMessageWriter_DFLogStart *ls) {
return new AP_Logger_DataFlash(front, ls);
return new AP_Logger_JEDEC(front, ls);
}
void Init(void) override;
bool CardInserted() const override { return !flash_died && df_NumPages > 0; }
Expand Down

0 comments on commit da7198c

Please sign in to comment.