AP_FlashIface: rename QSPIDevice to WSPIDevice

This commit is contained in:
Andy Piper 2022-08-17 15:17:14 +02:00 committed by Andrew Tridgell
parent c0b008902f
commit 11fba13dc8
2 changed files with 58 additions and 58 deletions

View File

@ -26,7 +26,7 @@
#include "AP_FlashIface_JEDEC.h" #include "AP_FlashIface_JEDEC.h"
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#ifdef HAL_BOOTLOADER_BUILD #ifdef HAL_BOOTLOADER_BUILD
#include <AP_HAL_ChibiOS/QSPIDevice.h> #include <AP_HAL_ChibiOS/WSPIDevice.h>
#include "../../Tools/AP_Bootloader/support.h" #include "../../Tools/AP_Bootloader/support.h"
#else #else
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -106,7 +106,7 @@ static const struct supported_device supported_devices[] = {
#define MAX_READ_SIZE 1024UL #define MAX_READ_SIZE 1024UL
#ifdef HAL_BOOTLOADER_BUILD #ifdef HAL_BOOTLOADER_BUILD
static ChibiOS::QSPIDeviceManager qspi; static ChibiOS::WSPIDeviceManager wspi;
#endif #endif
bool AP_FlashIface_JEDEC::init() bool AP_FlashIface_JEDEC::init()
@ -115,9 +115,9 @@ bool AP_FlashIface_JEDEC::init()
_dev = nullptr; _dev = nullptr;
for (uint8_t i = 0; i < ARRAY_SIZE(supported_devices); i++) { for (uint8_t i = 0; i < ARRAY_SIZE(supported_devices); i++) {
#ifdef HAL_BOOTLOADER_BUILD #ifdef HAL_BOOTLOADER_BUILD
_dev = qspi.get_device(supported_devices[i].name); _dev = wspi.get_device(supported_devices[i].name);
#else #else
_dev = hal.qspi->get_device(supported_devices[i].name); _dev = hal.wspi->get_device(supported_devices[i].name);
#endif #endif
if (_dev) { if (_dev) {
_dev_list_idx = i; _dev_list_idx = i;
@ -162,14 +162,14 @@ bool AP_FlashIface_JEDEC::init()
void AP_FlashIface_JEDEC::reset_device() void AP_FlashIface_JEDEC::reset_device()
{ {
// Get chip out of XIP mode // Get chip out of XIP mode
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
#ifndef HAL_BOOTLOADER_BUILD // this is required in order to run jedec_test with a regular bootloader #ifndef HAL_BOOTLOADER_BUILD // this is required in order to run jedec_test with a regular bootloader
_dev->get_semaphore()->take_blocking(); _dev->get_semaphore()->take_blocking();
#endif #endif
/* Single line CMD_RESET_MEMORY command.*/ /* Single line CMD_RESET_MEMORY command.*/
cmd.cmd = CMD_RESET_ENABLE; cmd.cmd = CMD_RESET_ENABLE;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE; cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -179,7 +179,7 @@ void AP_FlashIface_JEDEC::reset_device()
/* Single line N25Q_CMD_RESET_MEMORY command.*/ /* Single line N25Q_CMD_RESET_MEMORY command.*/
cmd.cmd = CMD_RESET_MEMORY; cmd.cmd = CMD_RESET_MEMORY;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE; cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -192,13 +192,13 @@ void AP_FlashIface_JEDEC::reset_device()
// Does initial configuration to bring up and setup chip // Does initial configuration to bring up and setup chip
bool AP_FlashIface_JEDEC::detect_device() bool AP_FlashIface_JEDEC::detect_device()
{ {
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
{ {
uint8_t buf[3] {}; uint8_t buf[3] {};
cmd.cmd = CMD_READ_ID; cmd.cmd = CMD_READ_ID;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_DATA_MODE_ONE_LINE; AP_HAL::WSPI::CFG_DATA_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -220,10 +220,10 @@ bool AP_FlashIface_JEDEC::detect_device()
uint32_t sfdp_header[2]; uint32_t sfdp_header[2];
cmd.cmd = CMD_READ_SFDP; cmd.cmd = CMD_READ_SFDP;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_MODE_ONE_LINE | AP_HAL::WSPI::CFG_ADDR_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_SIZE_24 | AP_HAL::WSPI::CFG_ADDR_SIZE_24 |
AP_HAL::QSPI::CFG_DATA_MODE_ONE_LINE; AP_HAL::WSPI::CFG_DATA_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 8; // 8 dummy cycles cmd.dummy = 8; // 8 dummy cycles
@ -437,7 +437,7 @@ bool AP_FlashIface_JEDEC::detect_device()
return true; return true;
} }
// Configures device to normal working state, currently 1-4-4 QSPI // Configures device to normal working state, currently 1-4-4 WSPI
bool AP_FlashIface_JEDEC::configure_device() bool AP_FlashIface_JEDEC::configure_device()
{ {
// Enable 1-4-4 mode // Enable 1-4-4 mode
@ -454,10 +454,10 @@ bool AP_FlashIface_JEDEC::configure_device()
write_enable(); write_enable();
wait_ready(); wait_ready();
AP_HAL::QSPIDevice::CommandHeader cmd { AP_HAL::WSPIDevice::CommandHeader cmd {
.cmd = 0x01, .cmd = 0x01,
.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | .cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_DATA_MODE_ONE_LINE, AP_HAL::WSPI::CFG_DATA_MODE_ONE_LINE,
.addr = 0, .addr = 0,
.alt = 0, .alt = 0,
.dummy = 0 .dummy = 0
@ -534,10 +534,10 @@ bool AP_FlashIface_JEDEC::modify_reg(uint8_t read_ins, uint8_t write_ins,
// reads a register value of chip using instruction // reads a register value of chip using instruction
bool AP_FlashIface_JEDEC::read_reg(uint8_t read_ins, uint8_t &read_val) bool AP_FlashIface_JEDEC::read_reg(uint8_t read_ins, uint8_t &read_val)
{ {
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = read_ins; cmd.cmd = read_ins;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_DATA_MODE_ONE_LINE; AP_HAL::WSPI::CFG_DATA_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -552,10 +552,10 @@ bool AP_FlashIface_JEDEC::read_reg(uint8_t read_ins, uint8_t &read_val)
// sends instruction to write a register value in the chip // sends instruction to write a register value in the chip
bool AP_FlashIface_JEDEC::write_reg(uint8_t read_ins, uint8_t write_val) bool AP_FlashIface_JEDEC::write_reg(uint8_t read_ins, uint8_t write_val)
{ {
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = read_ins; cmd.cmd = read_ins;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_DATA_MODE_ONE_LINE; AP_HAL::WSPI::CFG_DATA_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -567,12 +567,12 @@ bool AP_FlashIface_JEDEC::write_reg(uint8_t read_ins, uint8_t write_val)
return true; return true;
} }
// Sends QSPI command without data // Sends WSPI command without data
bool AP_FlashIface_JEDEC::send_cmd(uint8_t ins) bool AP_FlashIface_JEDEC::send_cmd(uint8_t ins)
{ {
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = ins; cmd.cmd = ins;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE; cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -603,9 +603,9 @@ bool AP_FlashIface_JEDEC::start_mass_erase(uint32_t &delay_ms, uint32_t &timeout
write_enable(); write_enable();
wait_ready(); wait_ready();
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = CMD_MASS_ERASE; cmd.cmd = CMD_MASS_ERASE;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE; cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE;
cmd.addr = 0; cmd.addr = 0;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -700,11 +700,11 @@ bool AP_FlashIface_JEDEC::start_erase_offset(uint32_t offset, uint32_t size, uin
write_enable(); write_enable();
wait_ready(); wait_ready();
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = ins; cmd.cmd = ins;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_MODE_ONE_LINE | AP_HAL::WSPI::CFG_ADDR_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_SIZE_24; AP_HAL::WSPI::CFG_ADDR_SIZE_24;
cmd.addr = offset; cmd.addr = offset;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -807,12 +807,12 @@ bool AP_FlashIface_JEDEC::start_program_offset(uint32_t offset, const uint8_t* d
write_enable(); write_enable();
wait_ready(); wait_ready();
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = CMD_PAGE_PROGRAM; cmd.cmd = CMD_PAGE_PROGRAM;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_MODE_ONE_LINE | AP_HAL::WSPI::CFG_ADDR_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_SIZE_24 | AP_HAL::WSPI::CFG_ADDR_SIZE_24 |
AP_HAL::QSPI::CFG_DATA_MODE_ONE_LINE; AP_HAL::WSPI::CFG_DATA_MODE_ONE_LINE;
cmd.addr = offset; cmd.addr = offset;
cmd.alt = 0; cmd.alt = 0;
cmd.dummy = 0; cmd.dummy = 0;
@ -853,16 +853,16 @@ bool AP_FlashIface_JEDEC::read(uint32_t offset, uint8_t* data, uint32_t size)
uint32_t read_ptr, read_size; uint32_t read_ptr, read_size;
for (read_ptr = offset; read_ptr < (offset+size); read_ptr+=MAX_READ_SIZE) { for (read_ptr = offset; read_ptr < (offset+size); read_ptr+=MAX_READ_SIZE) {
read_size = MIN((offset+size) - read_ptr, MAX_READ_SIZE); read_size = MIN((offset+size) - read_ptr, MAX_READ_SIZE);
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = _desc.fast_read_ins; cmd.cmd = _desc.fast_read_ins;
cmd.addr = read_ptr; cmd.addr = read_ptr;
cmd.alt = 0; cmd.alt = 0;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | cmd.cfg = AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_MODE_FOUR_LINES | AP_HAL::WSPI::CFG_ADDR_MODE_FOUR_LINES |
AP_HAL::QSPI::CFG_ADDR_SIZE_24 | AP_HAL::WSPI::CFG_ADDR_SIZE_24 |
AP_HAL::QSPI::CFG_DATA_MODE_FOUR_LINES | AP_HAL::WSPI::CFG_DATA_MODE_FOUR_LINES |
AP_HAL::QSPI::CFG_ALT_SIZE_8 | AP_HAL::WSPI::CFG_ALT_SIZE_8 |
AP_HAL::QSPI::CFG_ALT_MODE_FOUR_LINES; AP_HAL::WSPI::CFG_ALT_MODE_FOUR_LINES;
if (_desc.fast_read_mode_clocks == 1){ if (_desc.fast_read_mode_clocks == 1){
cmd.dummy = _desc.fast_read_dummy_cycles - 1; cmd.dummy = _desc.fast_read_dummy_cycles - 1;
} else { } else {
@ -927,7 +927,7 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr)
switch(_desc.entry_method) { switch(_desc.entry_method) {
case AP_FlashIface_JEDEC::XIP_ENTRY_METHOD_1: case AP_FlashIface_JEDEC::XIP_ENTRY_METHOD_1:
{ {
// Set QSPI module for XIP mode // Set WSPI module for XIP mode
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::QSPIDevice::CommandHeader cmd;
cmd.cmd = _desc.fast_read_ins; // generally 0xEB for 1-4-4 access cmd.cmd = _desc.fast_read_ins; // generally 0xEB for 1-4-4 access
cmd.alt = 0xF0; // add M0-7 bits in alt to make up 32-bit address phase, sec 8.2.11 W25Q64JV reference cmd.alt = 0xF0; // add M0-7 bits in alt to make up 32-bit address phase, sec 8.2.11 W25Q64JV reference
@ -954,17 +954,17 @@ bool AP_FlashIface_JEDEC::start_xip_mode(void** addr)
write_disable(); write_disable();
return false; return false;
} }
// Set QSPI module for XIP mode // Set WSPI module for XIP mode
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::WSPIDevice::CommandHeader cmd;
cmd.cmd = _desc.fast_read_ins; cmd.cmd = _desc.fast_read_ins;
cmd.alt = 0; cmd.alt = 0;
cmd.cfg = AP_HAL::QSPI::CFG_ADDR_SIZE_24 | cmd.cfg = AP_HAL::WSPI::CFG_ADDR_SIZE_24 |
AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE | AP_HAL::WSPI::CFG_CMD_MODE_ONE_LINE |
AP_HAL::QSPI::CFG_ADDR_MODE_FOUR_LINES | AP_HAL::WSPI::CFG_ADDR_MODE_FOUR_LINES |
AP_HAL::QSPI::CFG_DATA_MODE_FOUR_LINES | AP_HAL::WSPI::CFG_DATA_MODE_FOUR_LINES |
AP_HAL::QSPI::CFG_ALT_MODE_FOUR_LINES | /* Always 4 lines, note.*/ AP_HAL::WSPI::CFG_ALT_MODE_FOUR_LINES | /* Always 4 lines, note.*/
AP_HAL::QSPI::CFG_ALT_SIZE_8 | AP_HAL::WSPI::CFG_ALT_SIZE_8 |
AP_HAL::QSPI::CFG_SIOO; AP_HAL::WSPI::CFG_SIOO;
cmd.addr = 0; cmd.addr = 0;
// correct dummy bytes because of addition of alt bytes // correct dummy bytes because of addition of alt bytes
cmd.dummy = _desc.fast_read_dummy_cycles - 1; cmd.dummy = _desc.fast_read_dummy_cycles - 1;

View File

@ -225,7 +225,7 @@ protected:
// Does initial configuration to bring up and setup chip // Does initial configuration to bring up and setup chip
bool detect_device(); bool detect_device();
// Configures device to normal working state, currently 4-4-4 QSPI // Configures device to normal working state, currently 4-4-4 WSPI
bool configure_device(); bool configure_device();
// Enables commands that modify flash data or settings // Enables commands that modify flash data or settings
@ -247,13 +247,13 @@ protected:
// sends instruction to write a register value in the chip // sends instruction to write a register value in the chip
bool write_reg(uint8_t read_ins, uint8_t write_val); bool write_reg(uint8_t read_ins, uint8_t write_val);
// Sends QSPI command without data // Sends WSPI command without data
bool send_cmd(uint8_t ins); bool send_cmd(uint8_t ins);
// Is device in quad spi mode // Is device in quad spi mode
bool _quad_spi_mode; bool _quad_spi_mode;
AP_HAL::OwnPtr<AP_HAL::QSPIDevice> _dev; AP_HAL::OwnPtr<AP_HAL::WSPIDevice> _dev;
enum xip_entry_methods { enum xip_entry_methods {
XIP_ENTRY_METHOD_1, XIP_ENTRY_METHOD_1,