mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: rename class and hwdef related to w25nxx
This commit is contained in:
parent
ab407f3e27
commit
b66ecd8884
|
@ -218,6 +218,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
|||
|
||||
# enable logging to dataflash
|
||||
define HAL_LOGGING_DATAFLASH_ENABLED 1
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX
|
||||
|
||||
|
||||
|
|
|
@ -9,4 +9,4 @@ SPIDEV bmi270 SPI4 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
|
|||
|
||||
IMU BMI270 SPI:bmi270 ROTATION_PITCH_180_YAW_90
|
||||
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX
|
||||
|
|
|
@ -65,6 +65,6 @@ DMA_NOSHARE *UP SPI1*
|
|||
# Motor order implies Betaflight/X for standard ESCs
|
||||
define HAL_FRAME_TYPE_DEFAULT 12
|
||||
define HAL_LOGGING_DATAFLASH_ENABLED 1
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX
|
||||
|
||||
define AP_SCRIPTING_ENABLED 0
|
||||
|
|
|
@ -180,7 +180,7 @@ IMU BMI270 SPI:bmi270 ROTATION_PITCH_180
|
|||
IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180
|
||||
IMU Invensensev3 SPI:icm42688_2 ROTATION_ROLL_180_YAW_270
|
||||
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX
|
||||
|
||||
# DPS280 or SPL06 integrated on I2C bus
|
||||
BARO DPS280 I2C:0:0x76
|
||||
|
|
|
@ -159,7 +159,7 @@ SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
|
|||
|
||||
define HAL_LOGGING_DATAFLASH_ENABLED 1
|
||||
define HAL_OS_FATFS_IO 1
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV
|
||||
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX
|
||||
|
||||
|
||||
# ----------------- I2C compass & Baro -----------------
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
|
||||
#include "AP_Logger_File.h"
|
||||
#include "AP_Logger_Flash_JEDEC.h"
|
||||
#include "AP_Logger_W25N01GV.h"
|
||||
#include "AP_Logger_W25NXX.h"
|
||||
#include "AP_Logger_MAVLink.h"
|
||||
|
||||
#include <AP_InternalError/AP_InternalError.h>
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_Logger_W25N01GV.h"
|
||||
#include "AP_Logger_W25NXX.h"
|
||||
|
||||
#if HAL_LOGGING_DATAFLASH_ENABLED
|
||||
|
||||
|
@ -30,28 +30,28 @@ extern const AP_HAL::HAL& hal;
|
|||
#define JEDEC_STATUS_BUSY 0x01
|
||||
#define JEDEC_STATUS_WRITEPROTECT 0x02
|
||||
|
||||
#define W25N01G_STATUS_REG 0xC0
|
||||
#define W25N01G_PROT_REG 0xA0
|
||||
#define W25N01G_CONF_REG 0xB0
|
||||
#define W25N01G_STATUS_EFAIL 0x04
|
||||
#define W25N01G_STATUS_PFAIL 0x08
|
||||
#define W25NXX_STATUS_REG 0xC0
|
||||
#define W25NXX_PROT_REG 0xA0
|
||||
#define W25NXX_CONF_REG 0xB0
|
||||
#define W25NXX_STATUS_EFAIL 0x04
|
||||
#define W25NXX_STATUS_PFAIL 0x08
|
||||
|
||||
#define W25N01G_PROT_SRP1_ENABLE (1 << 0)
|
||||
#define W25N01G_PROT_WP_E_ENABLE (1 << 1)
|
||||
#define W25N01G_PROT_TB_ENABLE (1 << 2)
|
||||
#define W25N01G_PROT_PB0_ENABLE (1 << 3)
|
||||
#define W25N01G_PROT_PB1_ENABLE (1 << 4)
|
||||
#define W25N01G_PROT_PB2_ENABLE (1 << 5)
|
||||
#define W25N01G_PROT_PB3_ENABLE (1 << 6)
|
||||
#define W25N01G_PROT_SRP2_ENABLE (1 << 7)
|
||||
#define W25NXX_PROT_SRP1_ENABLE (1 << 0)
|
||||
#define W25NXX_PROT_WP_E_ENABLE (1 << 1)
|
||||
#define W25NXX_PROT_TB_ENABLE (1 << 2)
|
||||
#define W25NXX_PROT_PB0_ENABLE (1 << 3)
|
||||
#define W25NXX_PROT_PB1_ENABLE (1 << 4)
|
||||
#define W25NXX_PROT_PB2_ENABLE (1 << 5)
|
||||
#define W25NXX_PROT_PB3_ENABLE (1 << 6)
|
||||
#define W25NXX_PROT_SRP2_ENABLE (1 << 7)
|
||||
|
||||
#define W25N01G_CONFIG_ECC_ENABLE (1 << 4)
|
||||
#define W25N01G_CONFIG_BUFFER_READ_MODE (1 << 3)
|
||||
#define W25NXX_CONFIG_ECC_ENABLE (1 << 4)
|
||||
#define W25NXX_CONFIG_BUFFER_READ_MODE (1 << 3)
|
||||
|
||||
#define W25N01G_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled)
|
||||
#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 W25NXX_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled)
|
||||
#define W25NXX_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us
|
||||
#define W25NXX_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms
|
||||
#define W25NXX_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms
|
||||
|
||||
#define W25N01G_NUM_BLOCKS 1024
|
||||
#define W25N02K_NUM_BLOCKS 2048
|
||||
|
@ -59,11 +59,11 @@ extern const AP_HAL::HAL& hal;
|
|||
#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21
|
||||
#define JEDEC_ID_WINBOND_W25N02KV 0xEFAA22
|
||||
|
||||
void AP_Logger_W25N01GV::Init()
|
||||
void AP_Logger_W25NXX::Init()
|
||||
{
|
||||
dev = hal.spi->get_device("dataflash");
|
||||
if (!dev) {
|
||||
AP_HAL::panic("PANIC: AP_Logger W25N01GV device not found");
|
||||
AP_HAL::panic("PANIC: AP_Logger W25NXX device not found");
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -83,17 +83,17 @@ void AP_Logger_W25N01GV::Init()
|
|||
uint8_t b = JEDEC_DEVICE_RESET;
|
||||
dev->transfer(&b, 1, nullptr, 0);
|
||||
}
|
||||
hal.scheduler->delay(W25N01G_TIMEOUT_RESET_MS);
|
||||
hal.scheduler->delay(W25NXX_TIMEOUT_RESET_MS);
|
||||
|
||||
// disable write protection
|
||||
WriteStatusReg(W25N01G_PROT_REG, 0);
|
||||
WriteStatusReg(W25NXX_PROT_REG, 0);
|
||||
// enable ECC and buffer mode
|
||||
WriteStatusReg(W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE);
|
||||
WriteStatusReg(W25NXX_CONF_REG, W25NXX_CONFIG_ECC_ENABLE|W25NXX_CONFIG_BUFFER_READ_MODE);
|
||||
|
||||
printf("W25N01GV status: SR-1=0x%x, SR-2=0x%x, SR-3=0x%x\n",
|
||||
ReadStatusRegBits(W25N01G_PROT_REG),
|
||||
ReadStatusRegBits(W25N01G_CONF_REG),
|
||||
ReadStatusRegBits(W25N01G_STATUS_REG));
|
||||
printf("W25NXX status: SR-1=0x%x, SR-2=0x%x, SR-3=0x%x\n",
|
||||
ReadStatusRegBits(W25NXX_PROT_REG),
|
||||
ReadStatusRegBits(W25NXX_CONF_REG),
|
||||
ReadStatusRegBits(W25NXX_STATUS_REG));
|
||||
|
||||
AP_Logger_Block::Init();
|
||||
}
|
||||
|
@ -101,7 +101,7 @@ void AP_Logger_W25N01GV::Init()
|
|||
/*
|
||||
wait for busy flag to be cleared
|
||||
*/
|
||||
void AP_Logger_W25N01GV::WaitReady()
|
||||
void AP_Logger_W25NXX::WaitReady()
|
||||
{
|
||||
if (flash_died) {
|
||||
return;
|
||||
|
@ -118,7 +118,7 @@ void AP_Logger_W25N01GV::WaitReady()
|
|||
}
|
||||
}
|
||||
|
||||
bool AP_Logger_W25N01GV::getSectorCount(void)
|
||||
bool AP_Logger_W25NXX::getSectorCount(void)
|
||||
{
|
||||
WaitReady();
|
||||
|
||||
|
@ -158,7 +158,7 @@ bool AP_Logger_W25N01GV::getSectorCount(void)
|
|||
}
|
||||
|
||||
// Read the status register bits
|
||||
uint8_t AP_Logger_W25N01GV::ReadStatusRegBits(uint8_t bits)
|
||||
uint8_t AP_Logger_W25NXX::ReadStatusRegBits(uint8_t bits)
|
||||
{
|
||||
WITH_SEMAPHORE(dev_sem);
|
||||
uint8_t cmd[2] { JEDEC_READ_STATUS, bits };
|
||||
|
@ -167,7 +167,7 @@ uint8_t AP_Logger_W25N01GV::ReadStatusRegBits(uint8_t bits)
|
|||
return status;
|
||||
}
|
||||
|
||||
void AP_Logger_W25N01GV::WriteStatusReg(uint8_t reg, uint8_t bits)
|
||||
void AP_Logger_W25NXX::WriteStatusReg(uint8_t reg, uint8_t bits)
|
||||
{
|
||||
WaitReady();
|
||||
WITH_SEMAPHORE(dev_sem);
|
||||
|
@ -175,14 +175,14 @@ void AP_Logger_W25N01GV::WriteStatusReg(uint8_t reg, uint8_t bits)
|
|||
dev->transfer(cmd, 3, nullptr, 0);
|
||||
}
|
||||
|
||||
bool AP_Logger_W25N01GV::Busy()
|
||||
bool AP_Logger_W25NXX::Busy()
|
||||
{
|
||||
uint8_t status = ReadStatusRegBits(W25N01G_STATUS_REG);
|
||||
uint8_t status = ReadStatusRegBits(W25NXX_STATUS_REG);
|
||||
|
||||
if ((status & W25N01G_STATUS_PFAIL) != 0) {
|
||||
if ((status & W25NXX_STATUS_PFAIL) != 0) {
|
||||
printf("Program failure!\n");
|
||||
}
|
||||
if ((status & W25N01G_STATUS_EFAIL) != 0) {
|
||||
if ((status & W25NXX_STATUS_EFAIL) != 0) {
|
||||
printf("Erase failure!\n");
|
||||
}
|
||||
|
||||
|
@ -192,7 +192,7 @@ bool AP_Logger_W25N01GV::Busy()
|
|||
/*
|
||||
send a command with an address
|
||||
*/
|
||||
void AP_Logger_W25N01GV::send_command_addr(uint8_t command, uint32_t PageAdr)
|
||||
void AP_Logger_W25NXX::send_command_addr(uint8_t command, uint32_t PageAdr)
|
||||
{
|
||||
uint8_t cmd[4];
|
||||
cmd[0] = command;
|
||||
|
@ -203,7 +203,7 @@ void AP_Logger_W25N01GV::send_command_addr(uint8_t command, uint32_t PageAdr)
|
|||
dev->transfer(cmd, 4, nullptr, 0);
|
||||
}
|
||||
|
||||
void AP_Logger_W25N01GV::PageToBuffer(uint32_t pageNum)
|
||||
void AP_Logger_W25NXX::PageToBuffer(uint32_t pageNum)
|
||||
{
|
||||
if (pageNum == 0 || pageNum > df_NumPages+1) {
|
||||
printf("Invalid page read %u\n", pageNum);
|
||||
|
@ -247,7 +247,7 @@ void AP_Logger_W25N01GV::PageToBuffer(uint32_t pageNum)
|
|||
}
|
||||
}
|
||||
|
||||
void AP_Logger_W25N01GV::BufferToPage(uint32_t pageNum)
|
||||
void AP_Logger_W25NXX::BufferToPage(uint32_t pageNum)
|
||||
{
|
||||
if (pageNum == 0 || pageNum > df_NumPages+1) {
|
||||
printf("Invalid page write %u\n", pageNum);
|
||||
|
@ -288,7 +288,7 @@ void AP_Logger_W25N01GV::BufferToPage(uint32_t pageNum)
|
|||
/*
|
||||
erase one sector (sizes varies with hw)
|
||||
*/
|
||||
void AP_Logger_W25N01GV::SectorErase(uint32_t blockNum)
|
||||
void AP_Logger_W25NXX::SectorErase(uint32_t blockNum)
|
||||
{
|
||||
WriteEnable();
|
||||
WITH_SEMAPHORE(dev_sem);
|
||||
|
@ -300,12 +300,12 @@ void AP_Logger_W25N01GV::SectorErase(uint32_t blockNum)
|
|||
/*
|
||||
erase one 4k sector
|
||||
*/
|
||||
void AP_Logger_W25N01GV::Sector4kErase(uint32_t sectorNum)
|
||||
void AP_Logger_W25NXX::Sector4kErase(uint32_t sectorNum)
|
||||
{
|
||||
SectorErase(sectorNum);
|
||||
}
|
||||
|
||||
void AP_Logger_W25N01GV::StartErase()
|
||||
void AP_Logger_W25NXX::StartErase()
|
||||
{
|
||||
WriteEnable();
|
||||
|
||||
|
@ -319,7 +319,7 @@ void AP_Logger_W25N01GV::StartErase()
|
|||
printf("Dataflash: erase started\n");
|
||||
}
|
||||
|
||||
bool AP_Logger_W25N01GV::InErase()
|
||||
bool AP_Logger_W25NXX::InErase()
|
||||
{
|
||||
if (erase_start_ms && !Busy()) {
|
||||
if (erase_block < flash_blockNum) {
|
||||
|
@ -333,7 +333,7 @@ bool AP_Logger_W25N01GV::InErase()
|
|||
return erase_start_ms != 0;
|
||||
}
|
||||
|
||||
void AP_Logger_W25N01GV::WriteEnable(void)
|
||||
void AP_Logger_W25NXX::WriteEnable(void)
|
||||
{
|
||||
WaitReady();
|
||||
WITH_SEMAPHORE(dev_sem);
|
|
@ -9,13 +9,13 @@
|
|||
|
||||
#if HAL_LOGGING_DATAFLASH_ENABLED
|
||||
|
||||
class AP_Logger_W25N01GV : public AP_Logger_Block {
|
||||
class AP_Logger_W25NXX : public AP_Logger_Block {
|
||||
public:
|
||||
AP_Logger_W25N01GV(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) :
|
||||
AP_Logger_W25NXX(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_W25N01GV(front, ls);
|
||||
return new AP_Logger_W25NXX(front, ls);
|
||||
}
|
||||
void Init(void) override;
|
||||
bool CardInserted() const override { return !flash_died && df_NumPages > 0; }
|
Loading…
Reference in New Issue