ardupilot/libraries/AP_HAL_ChibiOS/QSPIDevice.cpp
Andy Piper 48c21299f8 AP_HAL_ChibiOS: hwdef for SPRacingH7
hwdef for DevEBoxH7v2
pin definitions for STM32H750
add QSPI to DevEBox bootloader
add external flash to DevEBox
rename EXTERNAL_PROG_FLASH_MB to EXT_FLASH_SIZE_MB
Add support for EXT_FLASH_RESERVE_START_KB and EXT_FLASH_RESERVE_END_KB
Disable HAL_ENABLE_SAVE_PERSISTENT_PARAMS when there is no bootloader flash available
relax storage health status with SD card backend
don't check SD card health unless USE_POSIX
binary sections rearranged on external ram
manage RAMFUNC through ldscript and optimize function placement in external flash
inline timer functions
optimize placement of ChibiOS and functions in ITCM and AXI RAM
fix chibios features on bootloader build with external flash
change H750 memory layout
increase line storage for SD card based parameters
comment external flash linker script
move vtables into DTCM
update ram map for H757
enable crashdump support with external flash
correct bootloader pins and generator on SPRacingH7/DevEBoxH7v2
setup external flash reserve regions
allow different RAM_MAP for external flash on H750 and H757
2022-02-09 12:47:55 +00:00

187 lines
5.4 KiB
C++

/*
* 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 <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" XSTR(STM32_QSPICLK) " needs to be divisible by selected clock" XSTR(HAL_QSPI1_CLK)
#endif
#if defined(STM32_WSPI_USE_QUADSPI2) && STM32_WSPI_USE_QUADSPI2
#if (STM32_QSPICLK % HAL_QSPI2_CLK)
#error "QSPI Clock" XSTR(STM32_QSPICLK) " needs to be divisible by selected clock" XSTR(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;
}
bool ret = true;
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)
{
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;
}
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;
}
// Enters Memory mapped or eXecution In Place or 0-4-4 mode
bool QSPIDevice::enter_xip_mode(void** map_ptr)
{
if (!acquire_bus(true)) {
return false;
}
wspiMapFlash(qspi_devices[device_desc.bus].driver, &mode, (uint8_t**)map_ptr);
acquire_bus(false);
return true;
}
bool QSPIDevice::exit_xip_mode()
{
if (!acquire_bus(true)) {
return false;
}
wspiUnmapFlash(qspi_devices[device_desc.bus].driver);
acquire_bus(false);
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)