mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: rename QSPIDevice to WSPIDevice
This commit is contained in:
parent
a73945c1b3
commit
f8dd6a1b2a
|
@ -23,10 +23,10 @@ namespace ChibiOS {
|
|||
class SPIDevice;
|
||||
class SPIDeviceDriver;
|
||||
class SPIDeviceManager;
|
||||
class QSPIBus;
|
||||
class QSPIDesc;
|
||||
class QSPIDevice;
|
||||
class QSPIDeviceManager;
|
||||
class WSPIBus;
|
||||
class WSPIDesc;
|
||||
class WSPIDevice;
|
||||
class WSPIDeviceManager;
|
||||
class Storage;
|
||||
class UARTDriver;
|
||||
class Util;
|
||||
|
|
|
@ -16,4 +16,4 @@
|
|||
#include "I2CDevice.h"
|
||||
#include "Flash.h"
|
||||
#include "DSP.h"
|
||||
#include "QSPIDevice.h"
|
||||
#include "WSPIDevice.h"
|
||||
|
|
|
@ -122,8 +122,8 @@ static Empty::Flash flashDriver;
|
|||
static ChibiOS::CANIface* canDrivers[HAL_NUM_CAN_IFACES];
|
||||
#endif
|
||||
|
||||
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST)
|
||||
static ChibiOS::QSPIDeviceManager qspiDeviceManager;
|
||||
#if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)
|
||||
static ChibiOS::WSPIDeviceManager wspiDeviceManager;
|
||||
#endif
|
||||
|
||||
#if HAL_WITH_IO_MCU
|
||||
|
@ -146,8 +146,8 @@ HAL_ChibiOS::HAL_ChibiOS() :
|
|||
&uartJDriver,
|
||||
&i2cDeviceManager,
|
||||
&spiDeviceManager,
|
||||
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST)
|
||||
&qspiDeviceManager,
|
||||
#if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)
|
||||
&wspiDeviceManager,
|
||||
#else
|
||||
nullptr,
|
||||
#endif
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
*/
|
||||
|
||||
#include <hal.h>
|
||||
#include "QSPIDevice.h"
|
||||
#include "WSPIDevice.h"
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
@ -28,21 +28,21 @@
|
|||
#include "Scheduler.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;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
static const struct QSPIDriverInfo {
|
||||
static const struct WSPIDriverInfo {
|
||||
WSPIDriver *driver;
|
||||
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 QSPIDEV_MODE3 STM32_DCR_CK_MODE
|
||||
#define WSPIDEV_MODE1 0
|
||||
#define WSPIDEV_MODE3 STM32_DCR_CK_MODE
|
||||
|
||||
// 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
|
||||
#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"
|
||||
#endif
|
||||
#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
|
||||
|
||||
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)
|
||||
{
|
||||
if (!acquire_bus(true)) {
|
||||
|
@ -74,14 +74,14 @@ bool QSPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|||
bool ret = true;
|
||||
if (send_len == 0 && recv_len == 0) {
|
||||
// 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) {
|
||||
// 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) {
|
||||
// This is a receive cmd,
|
||||
// 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 {
|
||||
// Can't handle this transaction type
|
||||
ret = false;
|
||||
|
@ -91,7 +91,7 @@ bool QSPIDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|||
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.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()) {
|
||||
return false;
|
||||
}
|
||||
if (acquire) {
|
||||
wspiAcquireBus(qspi_devices[device_desc.bus].driver);
|
||||
if (qspi_devices[device_desc.bus].driver->config != &bus.wspicfg) {
|
||||
wspiAcquireBus(wspi_devices[device_desc.bus].driver);
|
||||
if (wspi_devices[device_desc.bus].driver->config != &bus.wspicfg) {
|
||||
// Initialise and Start WSPI driver
|
||||
bus.wspicfg.end_cb = nullptr;
|
||||
bus.wspicfg.error_cb = nullptr;
|
||||
bus.wspicfg.dcr = STM32_DCR_FSIZE(device_desc.size_pow2) |
|
||||
STM32_DCR_CSHT(device_desc.ncs_clk_delay - 1) |
|
||||
device_desc.mode;
|
||||
wspiStart(qspi_devices[device_desc.bus].driver, &bus.wspicfg);
|
||||
wspiStart(wspi_devices[device_desc.bus].driver, &bus.wspicfg);
|
||||
}
|
||||
} else {
|
||||
wspiReleaseBus(qspi_devices[device_desc.bus].driver);
|
||||
wspiReleaseBus(wspi_devices[device_desc.bus].driver);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
// 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)) {
|
||||
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);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool QSPIDevice::exit_xip_mode()
|
||||
bool WSPIDevice::exit_xip_mode()
|
||||
{
|
||||
if (!acquire_bus(true)) {
|
||||
return false;
|
||||
}
|
||||
wspiUnmapFlash(qspi_devices[device_desc.bus].driver);
|
||||
wspiUnmapFlash(wspi_devices[device_desc.bus].driver);
|
||||
acquire_bus(false);
|
||||
return true;
|
||||
}
|
||||
|
@ -148,8 +148,8 @@ bool QSPIDevice::exit_xip_mode()
|
|||
/*
|
||||
return a SPIDevice given a string device name
|
||||
*/
|
||||
AP_HAL::OwnPtr<AP_HAL::QSPIDevice>
|
||||
QSPIDeviceManager::get_device(const char *name)
|
||||
AP_HAL::OwnPtr<AP_HAL::WSPIDevice>
|
||||
WSPIDeviceManager::get_device(const char *name)
|
||||
{
|
||||
/* Find the bus description in the table */
|
||||
uint8_t i;
|
||||
|
@ -159,21 +159,21 @@ QSPIDeviceManager::get_device(const char *name)
|
|||
}
|
||||
}
|
||||
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
|
||||
QSPIBus *busp;
|
||||
for (busp = buses; busp; busp = (QSPIBus *)busp->next) {
|
||||
WSPIBus *busp;
|
||||
for (busp = buses; busp; busp = (WSPIBus *)busp->next) {
|
||||
if (busp->bus == desc.bus) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (busp == nullptr) {
|
||||
// create a new one
|
||||
busp = new QSPIBus(desc.bus);
|
||||
busp = new WSPIBus(desc.bus);
|
||||
if (busp == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -183,7 +183,7 @@ QSPIDeviceManager::get_device(const char *name)
|
|||
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)
|
|
@ -21,10 +21,10 @@
|
|||
|
||||
#include <inttypes.h>
|
||||
#include <AP_HAL/HAL.h>
|
||||
#include <AP_HAL/QSPIDevice.h>
|
||||
#include <AP_HAL/WSPIDevice.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)
|
||||
#include "Semaphores.h"
|
||||
|
@ -37,8 +37,8 @@
|
|||
namespace ChibiOS
|
||||
{
|
||||
|
||||
struct QSPIDesc {
|
||||
QSPIDesc(const char *_name, uint8_t _bus,
|
||||
struct WSPIDesc {
|
||||
WSPIDesc(const char *_name, uint8_t _bus,
|
||||
uint32_t _mode, uint32_t _speed,
|
||||
uint8_t _size_pow2, uint8_t _ncs_clk_shift)
|
||||
: name(_name), bus(_bus), mode(_mode), speed(_speed),
|
||||
|
@ -47,7 +47,7 @@ struct QSPIDesc {
|
|||
}
|
||||
|
||||
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
|
||||
uint32_t mode; // clock mode
|
||||
uint32_t speed; // clock speed
|
||||
|
@ -56,27 +56,27 @@ struct QSPIDesc {
|
|||
|
||||
};
|
||||
|
||||
class QSPIBus : public DeviceBus
|
||||
class WSPIBus : public DeviceBus
|
||||
{
|
||||
public:
|
||||
QSPIBus(uint8_t _bus) :
|
||||
WSPIBus(uint8_t _bus) :
|
||||
DeviceBus(APM_SPI_PRIORITY, true),
|
||||
bus(_bus) {}
|
||||
|
||||
uint8_t bus;
|
||||
WSPIConfig wspicfg;
|
||||
bool qspi_started;
|
||||
bool wspi_started;
|
||||
};
|
||||
|
||||
class QSPIDevice : public AP_HAL::QSPIDevice
|
||||
class WSPIDevice : public AP_HAL::WSPIDevice
|
||||
{
|
||||
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),
|
||||
device_desc(_device_desc)
|
||||
{}
|
||||
|
@ -118,27 +118,27 @@ public:
|
|||
bool exit_xip_mode() override;
|
||||
|
||||
private:
|
||||
QSPIBus &bus;
|
||||
QSPIDesc &device_desc;
|
||||
WSPIBus &bus;
|
||||
WSPIDesc &device_desc;
|
||||
wspi_command_t mode;
|
||||
};
|
||||
|
||||
class QSPIDeviceManager : public AP_HAL::QSPIDeviceManager
|
||||
class WSPIDeviceManager : public AP_HAL::WSPIDeviceManager
|
||||
{
|
||||
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:
|
||||
static QSPIDesc device_table[];
|
||||
QSPIBus *buses;
|
||||
static WSPIDesc device_table[];
|
||||
WSPIBus *buses;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
#endif // #if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST)
|
||||
#endif // #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST)
|
|
@ -83,7 +83,7 @@ altlabel = {}
|
|||
# list of SPI devices
|
||||
spidev = []
|
||||
|
||||
# list of QSPI devices
|
||||
# list of WSPI devices
|
||||
qspidev = []
|
||||
|
||||
# dictionary of ROMFS files
|
||||
|
@ -92,7 +92,7 @@ romfs = {}
|
|||
# SPI bus list
|
||||
spi_list = []
|
||||
|
||||
# list of QSPI devices
|
||||
# list of WSPI devices
|
||||
qspi_list = []
|
||||
|
||||
# all config lines in order
|
||||
|
@ -1497,9 +1497,9 @@ def write_SPI_config(f):
|
|||
write_SPI_table(f)
|
||||
|
||||
|
||||
def write_QSPI_table(f):
|
||||
def write_WSPI_table(f):
|
||||
'''write SPI device table'''
|
||||
f.write('\n// QSPI device table\n')
|
||||
f.write('\n// WSPI device table\n')
|
||||
devlist = []
|
||||
for dev in qspidev:
|
||||
if len(dev) != 6:
|
||||
|
@ -1519,17 +1519,17 @@ def write_QSPI_table(f):
|
|||
|
||||
devidx = len(devlist)
|
||||
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)))
|
||||
devlist.append('HAL_QSPI_DEVICE%u' % devidx)
|
||||
f.write('#define HAL_QSPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||
devlist.append('HAL_WSPI_DEVICE%u' % devidx)
|
||||
f.write('#define HAL_WSPI_DEVICE_LIST %s\n\n' % ','.join(devlist))
|
||||
for dev in qspidev:
|
||||
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("\n")
|
||||
|
||||
|
||||
def write_QSPI_config(f):
|
||||
def write_WSPI_config(f):
|
||||
'''write SPI config defines'''
|
||||
global qspi_list
|
||||
# only the bootloader must reset the QSPI clock otherwise it is not possible to
|
||||
|
@ -1550,12 +1550,12 @@ def write_QSPI_config(f):
|
|||
devlist = []
|
||||
for dev in qspi_list:
|
||||
n = int(dev[7:])
|
||||
devlist.append('HAL_QSPI%u_CONFIG' % n)
|
||||
devlist.append('HAL_WSPI%u_CONFIG' % n)
|
||||
f.write(
|
||||
'#define HAL_QSPI%u_CONFIG { &WSPID%u, %u}\n'
|
||||
'#define HAL_WSPI%u_CONFIG { &WSPID%u, %u}\n'
|
||||
% (n, n, n))
|
||||
f.write('#define HAL_QSPI_BUS_LIST %s\n\n' % ','.join(devlist))
|
||||
write_QSPI_table(f)
|
||||
f.write('#define HAL_WSPI_BUS_LIST %s\n\n' % ','.join(devlist))
|
||||
write_WSPI_table(f)
|
||||
|
||||
def write_check_firmware(f):
|
||||
'''add AP_CHECK_FIRMWARE_ENABLED if needed'''
|
||||
|
@ -2546,7 +2546,7 @@ def write_hwdef_header(outfilename):
|
|||
|
||||
write_mcu_config(f)
|
||||
write_SPI_config(f)
|
||||
write_QSPI_config(f)
|
||||
write_WSPI_config(f)
|
||||
write_ADC_config(f)
|
||||
write_GPIO_config(f)
|
||||
write_IMU_config(f)
|
||||
|
|
Loading…
Reference in New Issue