AP_HAL_ChibiOS: rename QSPIDevice to WSPIDevice

This commit is contained in:
Andy Piper 2022-08-17 15:15:32 +02:00 committed by Andrew Tridgell
parent a73945c1b3
commit f8dd6a1b2a
6 changed files with 75 additions and 75 deletions

View File

@ -23,10 +23,10 @@ namespace ChibiOS {
class SPIDevice; class SPIDevice;
class SPIDeviceDriver; class SPIDeviceDriver;
class SPIDeviceManager; class SPIDeviceManager;
class QSPIBus; class WSPIBus;
class QSPIDesc; class WSPIDesc;
class QSPIDevice; class WSPIDevice;
class QSPIDeviceManager; class WSPIDeviceManager;
class Storage; class Storage;
class UARTDriver; class UARTDriver;
class Util; class Util;

View File

@ -16,4 +16,4 @@
#include "I2CDevice.h" #include "I2CDevice.h"
#include "Flash.h" #include "Flash.h"
#include "DSP.h" #include "DSP.h"
#include "QSPIDevice.h" #include "WSPIDevice.h"

View File

@ -122,8 +122,8 @@ static Empty::Flash flashDriver;
static ChibiOS::CANIface* canDrivers[HAL_NUM_CAN_IFACES]; static ChibiOS::CANIface* canDrivers[HAL_NUM_CAN_IFACES];
#endif #endif
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)
static ChibiOS::QSPIDeviceManager qspiDeviceManager; static ChibiOS::WSPIDeviceManager wspiDeviceManager;
#endif #endif
#if HAL_WITH_IO_MCU #if HAL_WITH_IO_MCU
@ -146,8 +146,8 @@ HAL_ChibiOS::HAL_ChibiOS() :
&uartJDriver, &uartJDriver,
&i2cDeviceManager, &i2cDeviceManager,
&spiDeviceManager, &spiDeviceManager,
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)
&qspiDeviceManager, &wspiDeviceManager,
#else #else
nullptr, nullptr,
#endif #endif

View File

@ -18,7 +18,7 @@
*/ */
#include <hal.h> #include <hal.h>
#include "QSPIDevice.h" #include "WSPIDevice.h"
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
@ -28,21 +28,21 @@
#include "Scheduler.h" #include "Scheduler.h"
#include <stdio.h> #include <stdio.h>
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)
using namespace ChibiOS; using namespace ChibiOS;
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
static const struct QSPIDriverInfo { static const struct WSPIDriverInfo {
WSPIDriver *driver; WSPIDriver *driver;
uint8_t busid; // used for device IDs in parameters uint8_t busid; // used for device IDs in parameters
} qspi_devices[] = { HAL_QSPI_BUS_LIST }; } wspi_devices[] = { HAL_WSPI_BUS_LIST };
#define QSPIDEV_MODE1 0 #define WSPIDEV_MODE1 0
#define QSPIDEV_MODE3 STM32_DCR_CK_MODE #define WSPIDEV_MODE3 STM32_DCR_CK_MODE
// device list comes from hwdef.dat // device list comes from hwdef.dat
QSPIDesc QSPIDeviceManager::device_table[] = { HAL_QSPI_DEVICE_LIST }; WSPIDesc WSPIDeviceManager::device_table[] = { HAL_WSPI_DEVICE_LIST };
// Check clock sanity during runtime // Check clock sanity during runtime
#if (STM32_QSPICLK < HAL_QSPI1_CLK) #if (STM32_QSPICLK < HAL_QSPI1_CLK)
@ -57,11 +57,11 @@ QSPIDesc QSPIDeviceManager::device_table[] = { HAL_QSPI_DEVICE_LIST };
#error "Flash speed must not be greater than QSPI Clock" #error "Flash speed must not be greater than QSPI Clock"
#endif #endif
#if (STM32_QSPICLK % HAL_QSPI2_CLK) #if (STM32_QSPICLK % HAL_QSPI2_CLK)
#warning "QSPI clock not an integer multiple of flash speed" #warning "WSPI clock not an integer multiple of flash speed"
#endif #endif
#endif #endif
bool QSPIDevice::transfer(const uint8_t *send, uint32_t send_len, bool WSPIDevice::transfer(const uint8_t *send, uint32_t send_len,
uint8_t *recv, uint32_t recv_len) uint8_t *recv, uint32_t recv_len)
{ {
if (!acquire_bus(true)) { if (!acquire_bus(true)) {
@ -74,14 +74,14 @@ bool QSPIDevice::transfer(const uint8_t *send, uint32_t send_len,
bool ret = true; bool ret = true;
if (send_len == 0 && recv_len == 0) { if (send_len == 0 && recv_len == 0) {
// This is just a command // This is just a command
ret = !wspiCommand(qspi_devices[device_desc.bus].driver, &mode); ret = !wspiCommand(wspi_devices[device_desc.bus].driver, &mode);
} else if (send_len > 0 && recv == 0) { } else if (send_len > 0 && recv == 0) {
// This is a send cmd // This is a send cmd
ret = !wspiSend(qspi_devices[device_desc.bus].driver, &mode, send_len, send); ret = !wspiSend(wspi_devices[device_desc.bus].driver, &mode, send_len, send);
} else if (send_len == 0 && recv_len >= 1) { } else if (send_len == 0 && recv_len >= 1) {
// This is a receive cmd, // This is a receive cmd,
// we only consume first byte of send // we only consume first byte of send
ret = !wspiReceive(qspi_devices[device_desc.bus].driver, &mode, recv_len, recv); ret = !wspiReceive(wspi_devices[device_desc.bus].driver, &mode, recv_len, recv);
} else { } else {
// Can't handle this transaction type // Can't handle this transaction type
ret = false; ret = false;
@ -91,7 +91,7 @@ bool QSPIDevice::transfer(const uint8_t *send, uint32_t send_len,
return ret; return ret;
} }
void QSPIDevice::set_cmd_header(const CommandHeader& cmd_hdr) void WSPIDevice::set_cmd_header(const CommandHeader& cmd_hdr)
{ {
mode.cmd = cmd_hdr.cmd; mode.cmd = cmd_hdr.cmd;
mode.cfg = cmd_hdr.cfg; mode.cfg = cmd_hdr.cfg;
@ -101,46 +101,46 @@ void QSPIDevice::set_cmd_header(const CommandHeader& cmd_hdr)
} }
bool QSPIDevice::acquire_bus(bool acquire) bool WSPIDevice::acquire_bus(bool acquire)
{ {
if (!bus.semaphore.check_owner()) { if (!bus.semaphore.check_owner()) {
return false; return false;
} }
if (acquire) { if (acquire) {
wspiAcquireBus(qspi_devices[device_desc.bus].driver); wspiAcquireBus(wspi_devices[device_desc.bus].driver);
if (qspi_devices[device_desc.bus].driver->config != &bus.wspicfg) { if (wspi_devices[device_desc.bus].driver->config != &bus.wspicfg) {
// Initialise and Start WSPI driver // Initialise and Start WSPI driver
bus.wspicfg.end_cb = nullptr; bus.wspicfg.end_cb = nullptr;
bus.wspicfg.error_cb = nullptr; bus.wspicfg.error_cb = nullptr;
bus.wspicfg.dcr = STM32_DCR_FSIZE(device_desc.size_pow2) | bus.wspicfg.dcr = STM32_DCR_FSIZE(device_desc.size_pow2) |
STM32_DCR_CSHT(device_desc.ncs_clk_delay - 1) | STM32_DCR_CSHT(device_desc.ncs_clk_delay - 1) |
device_desc.mode; device_desc.mode;
wspiStart(qspi_devices[device_desc.bus].driver, &bus.wspicfg); wspiStart(wspi_devices[device_desc.bus].driver, &bus.wspicfg);
} }
} else { } else {
wspiReleaseBus(qspi_devices[device_desc.bus].driver); wspiReleaseBus(wspi_devices[device_desc.bus].driver);
} }
return true; return true;
} }
// Enters Memory mapped or eXecution In Place or 0-4-4 mode // Enters Memory mapped or eXecution In Place or 0-4-4 mode
bool QSPIDevice::enter_xip_mode(void** map_ptr) bool WSPIDevice::enter_xip_mode(void** map_ptr)
{ {
if (!acquire_bus(true)) { if (!acquire_bus(true)) {
return false; return false;
} }
wspiMapFlash(qspi_devices[device_desc.bus].driver, &mode, (uint8_t**)map_ptr); wspiMapFlash(wspi_devices[device_desc.bus].driver, &mode, (uint8_t**)map_ptr);
acquire_bus(false); acquire_bus(false);
return true; return true;
} }
bool QSPIDevice::exit_xip_mode() bool WSPIDevice::exit_xip_mode()
{ {
if (!acquire_bus(true)) { if (!acquire_bus(true)) {
return false; return false;
} }
wspiUnmapFlash(qspi_devices[device_desc.bus].driver); wspiUnmapFlash(wspi_devices[device_desc.bus].driver);
acquire_bus(false); acquire_bus(false);
return true; return true;
} }
@ -148,8 +148,8 @@ bool QSPIDevice::exit_xip_mode()
/* /*
return a SPIDevice given a string device name return a SPIDevice given a string device name
*/ */
AP_HAL::OwnPtr<AP_HAL::QSPIDevice> AP_HAL::OwnPtr<AP_HAL::WSPIDevice>
QSPIDeviceManager::get_device(const char *name) WSPIDeviceManager::get_device(const char *name)
{ {
/* Find the bus description in the table */ /* Find the bus description in the table */
uint8_t i; uint8_t i;
@ -159,21 +159,21 @@ QSPIDeviceManager::get_device(const char *name)
} }
} }
if (i == ARRAY_SIZE(device_table)) { if (i == ARRAY_SIZE(device_table)) {
return AP_HAL::OwnPtr<AP_HAL::QSPIDevice>(nullptr); return AP_HAL::OwnPtr<AP_HAL::WSPIDevice>(nullptr);
} }
QSPIDesc &desc = device_table[i]; WSPIDesc &desc = device_table[i];
// find the bus // find the bus
QSPIBus *busp; WSPIBus *busp;
for (busp = buses; busp; busp = (QSPIBus *)busp->next) { for (busp = buses; busp; busp = (WSPIBus *)busp->next) {
if (busp->bus == desc.bus) { if (busp->bus == desc.bus) {
break; break;
} }
} }
if (busp == nullptr) { if (busp == nullptr) {
// create a new one // create a new one
busp = new QSPIBus(desc.bus); busp = new WSPIBus(desc.bus);
if (busp == nullptr) { if (busp == nullptr) {
return nullptr; return nullptr;
} }
@ -183,7 +183,7 @@ QSPIDeviceManager::get_device(const char *name)
buses = busp; buses = busp;
} }
return AP_HAL::OwnPtr<AP_HAL::QSPIDevice>(new QSPIDevice(*busp, desc)); return AP_HAL::OwnPtr<AP_HAL::WSPIDevice>(new WSPIDevice(*busp, desc));
} }
#endif // #if HAL_USE_QSPI == TRUE && defined(HAL_QPI_DEVICE_LIST) #endif // #if HAL_USE_WSPI == TRUE && defined(HAL_QPI_DEVICE_LIST)

View File

@ -21,10 +21,10 @@
#include <inttypes.h> #include <inttypes.h>
#include <AP_HAL/HAL.h> #include <AP_HAL/HAL.h>
#include <AP_HAL/QSPIDevice.h> #include <AP_HAL/WSPIDevice.h>
#include "AP_HAL_ChibiOS.h" #include "AP_HAL_ChibiOS.h"
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)
#if !defined(HAL_BOOTLOADER_BUILD) #if !defined(HAL_BOOTLOADER_BUILD)
#include "Semaphores.h" #include "Semaphores.h"
@ -37,8 +37,8 @@
namespace ChibiOS namespace ChibiOS
{ {
struct QSPIDesc { struct WSPIDesc {
QSPIDesc(const char *_name, uint8_t _bus, WSPIDesc(const char *_name, uint8_t _bus,
uint32_t _mode, uint32_t _speed, uint32_t _mode, uint32_t _speed,
uint8_t _size_pow2, uint8_t _ncs_clk_shift) uint8_t _size_pow2, uint8_t _ncs_clk_shift)
: name(_name), bus(_bus), mode(_mode), speed(_speed), : name(_name), bus(_bus), mode(_mode), speed(_speed),
@ -47,7 +47,7 @@ struct QSPIDesc {
} }
const char *name; // name of the device const char *name; // name of the device
uint8_t bus; // qspi bus being used uint8_t bus; // WSPI bus being used
uint8_t device; // device id uint8_t device; // device id
uint32_t mode; // clock mode uint32_t mode; // clock mode
uint32_t speed; // clock speed uint32_t speed; // clock speed
@ -56,27 +56,27 @@ struct QSPIDesc {
}; };
class QSPIBus : public DeviceBus class WSPIBus : public DeviceBus
{ {
public: public:
QSPIBus(uint8_t _bus) : WSPIBus(uint8_t _bus) :
DeviceBus(APM_SPI_PRIORITY, true), DeviceBus(APM_SPI_PRIORITY, true),
bus(_bus) {} bus(_bus) {}
uint8_t bus; uint8_t bus;
WSPIConfig wspicfg; WSPIConfig wspicfg;
bool qspi_started; bool wspi_started;
}; };
class QSPIDevice : public AP_HAL::QSPIDevice class WSPIDevice : public AP_HAL::WSPIDevice
{ {
public: public:
static QSPIDevice *from(AP_HAL::QSPIDevice *dev) static WSPIDevice *from(AP_HAL::WSPIDevice *dev)
{ {
return static_cast<QSPIDevice*>(dev); return static_cast<WSPIDevice*>(dev);
} }
QSPIDevice(QSPIBus &_bus, QSPIDesc &_device_desc) : WSPIDevice(WSPIBus &_bus, WSPIDesc &_device_desc) :
bus(_bus), bus(_bus),
device_desc(_device_desc) device_desc(_device_desc)
{} {}
@ -118,27 +118,27 @@ public:
bool exit_xip_mode() override; bool exit_xip_mode() override;
private: private:
QSPIBus &bus; WSPIBus &bus;
QSPIDesc &device_desc; WSPIDesc &device_desc;
wspi_command_t mode; wspi_command_t mode;
}; };
class QSPIDeviceManager : public AP_HAL::QSPIDeviceManager class WSPIDeviceManager : public AP_HAL::WSPIDeviceManager
{ {
public: public:
friend class QSPIDevice; friend class WSPIDevice;
static QSPIDeviceManager *from(AP_HAL::QSPIDeviceManager *qspi_mgr) static WSPIDeviceManager *from(AP_HAL::WSPIDeviceManager *wspi_mgr)
{ {
return static_cast<QSPIDeviceManager*>(qspi_mgr); return static_cast<WSPIDeviceManager*>(wspi_mgr);
} }
AP_HAL::OwnPtr<AP_HAL::QSPIDevice> get_device(const char *name) override; AP_HAL::OwnPtr<AP_HAL::WSPIDevice> get_device(const char *name) override;
private: private:
static QSPIDesc device_table[]; static WSPIDesc device_table[];
QSPIBus *buses; WSPIBus *buses;
}; };
} }
#endif // #if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) #endif // #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)

View File

@ -83,7 +83,7 @@ altlabel = {}
# list of SPI devices # list of SPI devices
spidev = [] spidev = []
# list of QSPI devices # list of WSPI devices
qspidev = [] qspidev = []
# dictionary of ROMFS files # dictionary of ROMFS files
@ -92,7 +92,7 @@ romfs = {}
# SPI bus list # SPI bus list
spi_list = [] spi_list = []
# list of QSPI devices # list of WSPI devices
qspi_list = [] qspi_list = []
# all config lines in order # all config lines in order
@ -1497,9 +1497,9 @@ def write_SPI_config(f):
write_SPI_table(f) write_SPI_table(f)
def write_QSPI_table(f): def write_WSPI_table(f):
'''write SPI device table''' '''write SPI device table'''
f.write('\n// QSPI device table\n') f.write('\n// WSPI device table\n')
devlist = [] devlist = []
for dev in qspidev: for dev in qspidev:
if len(dev) != 6: if len(dev) != 6:
@ -1519,17 +1519,17 @@ def write_QSPI_table(f):
devidx = len(devlist) devidx = len(devlist)
f.write( f.write(
'#define HAL_QSPI_DEVICE%-2u QSPIDesc(%-17s, %2u, QSPIDEV_%s, %7s, %2u, %2u)\n' '#define HAL_WSPI_DEVICE%-2u WSPIDesc(%-17s, %2u, WSPIDEV_%s, %7s, %2u, %2u)\n'
% (devidx, name, qspi_list.index(bus), mode, speed, int(size_pow2), int(ncs_clk_delay))) % (devidx, name, qspi_list.index(bus), mode, speed, int(size_pow2), int(ncs_clk_delay)))
devlist.append('HAL_QSPI_DEVICE%u' % devidx) devlist.append('HAL_WSPI_DEVICE%u' % devidx)
f.write('#define HAL_QSPI_DEVICE_LIST %s\n\n' % ','.join(devlist)) f.write('#define HAL_WSPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
for dev in qspidev: for dev in qspidev:
f.write("#define HAL_HAS_WSPI_%s 1\n" % dev[0].upper().replace("-", "_")) f.write("#define HAL_HAS_WSPI_%s 1\n" % dev[0].upper().replace("-", "_"))
f.write("#define HAL_QSPI%d_CLK (%s)" % (int(bus[7:]), speed)) f.write("#define HAL_QSPI%d_CLK (%s)" % (int(bus[7:]), speed))
f.write("\n") f.write("\n")
def write_QSPI_config(f): def write_WSPI_config(f):
'''write SPI config defines''' '''write SPI config defines'''
global qspi_list global qspi_list
# only the bootloader must reset the QSPI clock otherwise it is not possible to # only the bootloader must reset the QSPI clock otherwise it is not possible to
@ -1550,12 +1550,12 @@ def write_QSPI_config(f):
devlist = [] devlist = []
for dev in qspi_list: for dev in qspi_list:
n = int(dev[7:]) n = int(dev[7:])
devlist.append('HAL_QSPI%u_CONFIG' % n) devlist.append('HAL_WSPI%u_CONFIG' % n)
f.write( f.write(
'#define HAL_QSPI%u_CONFIG { &WSPID%u, %u}\n' '#define HAL_WSPI%u_CONFIG { &WSPID%u, %u}\n'
% (n, n, n)) % (n, n, n))
f.write('#define HAL_QSPI_BUS_LIST %s\n\n' % ','.join(devlist)) f.write('#define HAL_WSPI_BUS_LIST %s\n\n' % ','.join(devlist))
write_QSPI_table(f) write_WSPI_table(f)
def write_check_firmware(f): def write_check_firmware(f):
'''add AP_CHECK_FIRMWARE_ENABLED if needed''' '''add AP_CHECK_FIRMWARE_ENABLED if needed'''
@ -2546,7 +2546,7 @@ def write_hwdef_header(outfilename):
write_mcu_config(f) write_mcu_config(f)
write_SPI_config(f) write_SPI_config(f)
write_QSPI_config(f) write_WSPI_config(f)
write_ADC_config(f) write_ADC_config(f)
write_GPIO_config(f) write_GPIO_config(f)
write_IMU_config(f) write_IMU_config(f)