15 changed files with 424 additions and 23 deletions
@ -0,0 +1,168 @@
@@ -0,0 +1,168 @@
|
||||
/*
|
||||
* This file is free software: you can redistribute it and/or modify it |
||||
* under the terms of the GNU General Public License as published by the |
||||
* Free Software Foundation, either version 3 of the License, or |
||||
* (at your option) any later version. |
||||
* |
||||
* This file is distributed in the hope that it will be useful, but |
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. |
||||
* See the GNU General Public License for more details. |
||||
* |
||||
* You should have received a copy of the GNU General Public License along |
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
* |
||||
* Code by
|
||||
* Andy Piper |
||||
* Siddharth Bharat Purohit, Cubepilot Pty. Ltd. |
||||
*/ |
||||
|
||||
#include "QSPIDevice.h" |
||||
|
||||
#include <AP_HAL/AP_HAL.h> |
||||
#include <AP_Math/AP_Math.h> |
||||
#include <AP_HAL/utility/OwnPtr.h> |
||||
#include <AP_InternalError/AP_InternalError.h> |
||||
#include "Util.h" |
||||
#include "Scheduler.h" |
||||
#include "Semaphores.h" |
||||
#include <stdio.h> |
||||
#include "hwdef/common/stm32_util.h" |
||||
|
||||
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) |
||||
|
||||
using namespace ChibiOS; |
||||
extern const AP_HAL::HAL& hal; |
||||
|
||||
static const struct QSPIDriverInfo { |
||||
WSPIDriver *driver; |
||||
uint8_t busid; // used for device IDs in parameters
|
||||
} qspi_devices[] = { HAL_QSPI_BUS_LIST }; |
||||
|
||||
#define QSPIDEV_MODE1 0 |
||||
#define QSPIDEV_MODE3 STM32_DCR_CK_MODE |
||||
|
||||
// device list comes from hwdef.dat
|
||||
QSPIDesc QSPIDeviceManager::device_table[] = { HAL_QSPI_DEVICE_LIST }; |
||||
|
||||
// Check clock sanity during runtime
|
||||
#define XSTR(x) STR(x) |
||||
#define STR(x) #x |
||||
|
||||
#if (STM32_QSPICLK % HAL_QSPI1_CLK) |
||||
#error "QSPI Clock" STR(STM32_QSPICLK) " needs to be divisible by selected clock" STR(HAL_QSPI1_CLK) |
||||
#endif |
||||
|
||||
#if defined(STM32_WSPI_USE_QUADSPI2) && STM32_WSPI_USE_QUADSPI2 |
||||
#if (STM32_QSPICLK % HAL_QSPI2_CLK) |
||||
#error "QSPI Clock" STR(STM32_QSPICLK) " needs to be divisible by selected clock" STR(HAL_QSPI2_CLK) |
||||
#endif |
||||
#endif |
||||
|
||||
bool QSPIDevice::transfer(const uint8_t *send, uint32_t send_len, |
||||
uint8_t *recv, uint32_t recv_len) |
||||
{ |
||||
if (!acquire_bus(true)) { |
||||
return false; |
||||
} |
||||
if (!bus.bouncebuffer_setup(send, send_len, recv, recv_len)) { |
||||
acquire_bus(false); |
||||
return false; |
||||
} |
||||
wspi_command_t mode; |
||||
bool ret = true; |
||||
mode.cmd = _cmd_hdr.cmd; |
||||
mode.cfg = _cmd_hdr.cfg; |
||||
mode.addr = _cmd_hdr.addr; |
||||
mode.alt = _cmd_hdr.alt; |
||||
mode.dummy = _cmd_hdr.dummy; |
||||
|
||||
if (send_len == 0 && recv_len == 0) { |
||||
// This is just a command
|
||||
ret = wspiCommand(qspi_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); |
||||
} 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); |
||||
} else { |
||||
// Can't handle this transaction type
|
||||
ret = false; |
||||
} |
||||
bus.bouncebuffer_finish(send, recv, recv_len); |
||||
acquire_bus(false); |
||||
return ret; |
||||
} |
||||
|
||||
void QSPIDevice::set_cmd_header(const CommandHeader& cmd_hdr) |
||||
{ |
||||
_cmd_hdr = cmd_hdr; |
||||
} |
||||
|
||||
|
||||
bool QSPIDevice::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) { |
||||
// 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); |
||||
} |
||||
} else { |
||||
wspiReleaseBus(qspi_devices[device_desc.bus].driver); |
||||
} |
||||
return true; |
||||
} |
||||
|
||||
/*
|
||||
return a SPIDevice given a string device name |
||||
*/ |
||||
AP_HAL::OwnPtr<AP_HAL::QSPIDevice> |
||||
QSPIDeviceManager::get_device(const char *name) |
||||
{ |
||||
/* Find the bus description in the table */ |
||||
uint8_t i; |
||||
for (i = 0; i<ARRAY_SIZE(device_table); i++) { |
||||
if (strcmp(device_table[i].name, name) == 0) { |
||||
break; |
||||
} |
||||
} |
||||
if (i == ARRAY_SIZE(device_table)) { |
||||
return AP_HAL::OwnPtr<AP_HAL::QSPIDevice>(nullptr); |
||||
} |
||||
|
||||
QSPIDesc &desc = device_table[i]; |
||||
|
||||
// find the bus
|
||||
QSPIBus *busp; |
||||
for (busp = buses; busp; busp = (QSPIBus *)busp->next) { |
||||
if (busp->bus == desc.bus) { |
||||
break; |
||||
} |
||||
} |
||||
if (busp == nullptr) { |
||||
// create a new one
|
||||
busp = new QSPIBus(desc.bus); |
||||
if (busp == nullptr) { |
||||
return nullptr; |
||||
} |
||||
busp->next = buses; |
||||
busp->bus = desc.bus; |
||||
|
||||
buses = busp; |
||||
} |
||||
|
||||
return AP_HAL::OwnPtr<AP_HAL::QSPIDevice>(new QSPIDevice(*busp, desc)); |
||||
} |
||||
|
||||
#endif // #if HAL_USE_QSPI == TRUE && defined(HAL_QPI_DEVICE_LIST)
|
@ -0,0 +1,132 @@
@@ -0,0 +1,132 @@
|
||||
/*
|
||||
* This file is free software: you can redistribute it and/or modify it |
||||
* under the terms of the GNU General Public License as published by the |
||||
* Free Software Foundation, either version 3 of the License, or |
||||
* (at your option) any later version. |
||||
* |
||||
* This file is distributed in the hope that it will be useful, but |
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of |
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. |
||||
* See the GNU General Public License for more details. |
||||
* |
||||
* You should have received a copy of the GNU General Public License along |
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
* |
||||
* Code by
|
||||
* Andy Piper |
||||
* Siddharth Bharat Purohit, Cubepilot Pty. Ltd. |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
#include <inttypes.h> |
||||
#include <AP_HAL/HAL.h> |
||||
#include <AP_HAL/QSPIDevice.h> |
||||
#include "AP_HAL_ChibiOS.h" |
||||
|
||||
#if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST) |
||||
|
||||
#include "Semaphores.h" |
||||
#include "Scheduler.h" |
||||
#include "Device.h" |
||||
|
||||
namespace ChibiOS |
||||
{ |
||||
|
||||
struct QSPIDesc { |
||||
QSPIDesc(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), |
||||
size_pow2(_size_pow2), ncs_clk_delay(_ncs_clk_shift) |
||||
{ |
||||
} |
||||
|
||||
const char *name; // name of the device
|
||||
uint8_t bus; // qspi bus being used
|
||||
uint8_t device; // device id
|
||||
uint32_t mode; // clock mode
|
||||
uint32_t speed; // clock speed
|
||||
uint8_t size_pow2; // size as power of 2
|
||||
uint8_t ncs_clk_delay; // number of clk cycles to wait while transitioning NCS
|
||||
|
||||
}; |
||||
|
||||
class QSPIBus : public DeviceBus |
||||
{ |
||||
public: |
||||
QSPIBus(uint8_t _bus) : |
||||
DeviceBus(APM_SPI_PRIORITY, true), |
||||
bus(_bus) {} |
||||
|
||||
uint8_t bus; |
||||
WSPIConfig wspicfg; |
||||
bool qspi_started; |
||||
}; |
||||
|
||||
class QSPIDevice : public AP_HAL::QSPIDevice |
||||
{ |
||||
public: |
||||
static QSPIDevice *from(AP_HAL::QSPIDevice *dev) |
||||
{ |
||||
return static_cast<QSPIDevice*>(dev); |
||||
} |
||||
|
||||
QSPIDevice(QSPIBus &_bus, QSPIDesc &_device_desc) : |
||||
bus(_bus), |
||||
device_desc(_device_desc) |
||||
{} |
||||
|
||||
bool set_speed(Speed speed) override |
||||
{ |
||||
return true; |
||||
} |
||||
|
||||
PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb) override |
||||
{ |
||||
return nullptr; |
||||
} |
||||
bool adjust_periodic_callback(PeriodicHandle h, uint32_t period_usec) override |
||||
{ |
||||
return false; |
||||
} |
||||
|
||||
/* See AP_HAL::Device::transfer() */ |
||||
bool transfer(const uint8_t *send, uint32_t send_len, |
||||
uint8_t *recv, uint32_t recv_len) override; |
||||
|
||||
void set_cmd_header(const CommandHeader& cmd_hdr) override; |
||||
|
||||
AP_HAL::Semaphore* get_semaphore() override |
||||
{ |
||||
// if asking for invalid bus number use bus 0 semaphore
|
||||
return &bus.semaphore; |
||||
} |
||||
|
||||
bool acquire_bus(bool acquire); |
||||
|
||||
private: |
||||
QSPIBus &bus; |
||||
QSPIDesc &device_desc; |
||||
CommandHeader _cmd_hdr; |
||||
}; |
||||
|
||||
class QSPIDeviceManager : public AP_HAL::QSPIDeviceManager |
||||
{ |
||||
public: |
||||
friend class QSPIDevice; |
||||
|
||||
static QSPIDeviceManager *from(AP_HAL::QSPIDeviceManager *qspi_mgr) |
||||
{ |
||||
return static_cast<QSPIDeviceManager*>(qspi_mgr); |
||||
} |
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::QSPIDevice> get_device(const char *name) override; |
||||
private: |
||||
static QSPIDesc device_table[]; |
||||
QSPIBus *buses; |
||||
}; |
||||
|
||||
} |
||||
|
||||
#endif // #if HAL_USE_WSPI == TRUE && defined(HAL_QSPI_DEVICE_LIST)
|
Loading…
Reference in new issue