AP_HAL: add support for QSPIDevice
This commit is contained in:
parent
abc26d1993
commit
a323807644
@ -33,6 +33,10 @@ namespace AP_HAL {
|
|||||||
class OpticalFlow;
|
class OpticalFlow;
|
||||||
class DSP;
|
class DSP;
|
||||||
|
|
||||||
|
class QSPIDevice;
|
||||||
|
class QSPIDeviceDriver;
|
||||||
|
class QSPIDeviceManager;
|
||||||
|
|
||||||
class CANIface;
|
class CANIface;
|
||||||
class CANFrame;
|
class CANFrame;
|
||||||
|
|
||||||
|
@ -34,6 +34,7 @@ public:
|
|||||||
BUS_TYPE_SITL = 4,
|
BUS_TYPE_SITL = 4,
|
||||||
BUS_TYPE_MSP = 5,
|
BUS_TYPE_MSP = 5,
|
||||||
BUS_TYPE_SERIAL = 6,
|
BUS_TYPE_SERIAL = 6,
|
||||||
|
BUS_TYPE_QSPI = 7,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum Speed {
|
enum Speed {
|
||||||
@ -41,6 +42,16 @@ public:
|
|||||||
SPEED_LOW,
|
SPEED_LOW,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Used for comms with devices that support wide SPI
|
||||||
|
// like quad spi
|
||||||
|
struct CommandHeader {
|
||||||
|
uint32_t cmd; //Command phase data.
|
||||||
|
uint32_t cfg; //Transfer configuration field.
|
||||||
|
uint32_t addr; //Address phase data.
|
||||||
|
uint32_t alt; // Alternate phase data.
|
||||||
|
uint32_t dummy; // Number of dummy cycles to be inserted.
|
||||||
|
};
|
||||||
|
|
||||||
FUNCTOR_TYPEDEF(PeriodicCb, void);
|
FUNCTOR_TYPEDEF(PeriodicCb, void);
|
||||||
typedef void* PeriodicHandle;
|
typedef void* PeriodicHandle;
|
||||||
|
|
||||||
@ -105,6 +116,14 @@ public:
|
|||||||
virtual bool transfer(const uint8_t *send, uint32_t send_len,
|
virtual bool transfer(const uint8_t *send, uint32_t send_len,
|
||||||
uint8_t *recv, uint32_t recv_len) = 0;
|
uint8_t *recv, uint32_t recv_len) = 0;
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Sets the required flags before transaction starts
|
||||||
|
* this is to be used by Wide SPI communication interfaces like
|
||||||
|
* Dual/Quad/Octo SPI
|
||||||
|
*/
|
||||||
|
virtual void set_cmd_header(const CommandHeader& cmd_hdr) {}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Wrapper function over #transfer() to read recv_len registers, starting
|
* Wrapper function over #transfer() to read recv_len registers, starting
|
||||||
* by first_reg, into the array pointed by recv. The read flag passed to
|
* by first_reg, into the array pointed by recv. The read flag passed to
|
||||||
|
@ -9,6 +9,7 @@ class AP_Param;
|
|||||||
#include "RCInput.h"
|
#include "RCInput.h"
|
||||||
#include "RCOutput.h"
|
#include "RCOutput.h"
|
||||||
#include "SPIDevice.h"
|
#include "SPIDevice.h"
|
||||||
|
#include "QSPIDevice.h"
|
||||||
#include "Storage.h"
|
#include "Storage.h"
|
||||||
#include "UARTDriver.h"
|
#include "UARTDriver.h"
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
@ -30,6 +31,7 @@ public:
|
|||||||
AP_HAL::UARTDriver* _uartI, // extra4
|
AP_HAL::UARTDriver* _uartI, // extra4
|
||||||
AP_HAL::I2CDeviceManager* _i2c_mgr,
|
AP_HAL::I2CDeviceManager* _i2c_mgr,
|
||||||
AP_HAL::SPIDeviceManager* _spi,
|
AP_HAL::SPIDeviceManager* _spi,
|
||||||
|
AP_HAL::QSPIDeviceManager* _qspi,
|
||||||
AP_HAL::AnalogIn* _analogin,
|
AP_HAL::AnalogIn* _analogin,
|
||||||
AP_HAL::Storage* _storage,
|
AP_HAL::Storage* _storage,
|
||||||
AP_HAL::UARTDriver* _console,
|
AP_HAL::UARTDriver* _console,
|
||||||
@ -58,6 +60,7 @@ public:
|
|||||||
uartI(_uartI),
|
uartI(_uartI),
|
||||||
i2c_mgr(_i2c_mgr),
|
i2c_mgr(_i2c_mgr),
|
||||||
spi(_spi),
|
spi(_spi),
|
||||||
|
qspi(_qspi),
|
||||||
analogin(_analogin),
|
analogin(_analogin),
|
||||||
storage(_storage),
|
storage(_storage),
|
||||||
console(_console),
|
console(_console),
|
||||||
@ -116,6 +119,7 @@ private:
|
|||||||
public:
|
public:
|
||||||
AP_HAL::I2CDeviceManager* i2c_mgr;
|
AP_HAL::I2CDeviceManager* i2c_mgr;
|
||||||
AP_HAL::SPIDeviceManager* spi;
|
AP_HAL::SPIDeviceManager* spi;
|
||||||
|
AP_HAL::QSPIDeviceManager* qspi;
|
||||||
AP_HAL::AnalogIn* analogin;
|
AP_HAL::AnalogIn* analogin;
|
||||||
AP_HAL::Storage* storage;
|
AP_HAL::Storage* storage;
|
||||||
AP_HAL::UARTDriver* console;
|
AP_HAL::UARTDriver* console;
|
||||||
|
125
libraries/AP_HAL/QSPIDevice.h
Normal file
125
libraries/AP_HAL/QSPIDevice.h
Normal file
@ -0,0 +1,125 @@
|
|||||||
|
/*
|
||||||
|
* 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 and Siddharth Bharat Purohit
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <inttypes.h>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
#include "AP_HAL_Namespace.h"
|
||||||
|
#include "Device.h"
|
||||||
|
#include "utility/OwnPtr.h"
|
||||||
|
|
||||||
|
#ifndef HAL_USE_QSPI_DEFAULT_CFG
|
||||||
|
#define HAL_USE_QSPI_DEFAULT_CFG 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
namespace AP_HAL
|
||||||
|
{
|
||||||
|
|
||||||
|
// Underlying HAL implementation can override these
|
||||||
|
#if HAL_USE_QSPI_DEFAULT_CFG
|
||||||
|
namespace QSPI
|
||||||
|
{
|
||||||
|
constexpr uint32_t CFG_CMD_MODE_MASK = (3LU << 8LU);
|
||||||
|
constexpr uint32_t CFG_CMD_MODE_NONE = (0LU << 8LU);
|
||||||
|
constexpr uint32_t CFG_CMD_MODE_ONE_LINE = (1LU << 8LU);
|
||||||
|
constexpr uint32_t CFG_CMD_MODE_TWO_LINES = (2LU << 8LU);
|
||||||
|
constexpr uint32_t CFG_CMD_MODE_FOUR_LINES = (3LU << 8LU);
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_CMD_SIZE_MASK = 0LU;
|
||||||
|
constexpr uint32_t CFG_CMD_SIZE_8 = 0LU;
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_ADDR_MODE_MASK = (3LU << 10LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_MODE_NONE = (0LU << 10LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_MODE_ONE_LINE = (1LU << 10LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_MODE_TWO_LINES = (2LU << 10LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_MODE_FOUR_LINES = (3LU << 10LU);
|
||||||
|
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_ADDR_SIZE_MASK = (3LU << 12LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_SIZE_8 = (0LU << 12LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_SIZE_16 = (1LU << 12LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_SIZE_24 = (2LU << 12LU);
|
||||||
|
constexpr uint32_t CFG_ADDR_SIZE_32 = (3LU << 12LU);
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_ALT_MODE_MASK = (3LU << 14LU);
|
||||||
|
constexpr uint32_t CFG_ALT_MODE_NONE = (0LU << 14LU);
|
||||||
|
constexpr uint32_t CFG_ALT_MODE_ONE_LINE = (1LU << 14LU);
|
||||||
|
constexpr uint32_t CFG_ALT_MODE_TWO_LINES = (2LU << 14LU);
|
||||||
|
constexpr uint32_t CFG_ALT_MODE_FOUR_LINES = (3LU << 14LU);
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_ALT_DDR = (1LU << 31LU);
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_ALT_SIZE_MASK = (3LU << 16LU);
|
||||||
|
constexpr uint32_t CFG_ALT_SIZE_8 = (0LU << 16LU);
|
||||||
|
constexpr uint32_t CFG_ALT_SIZE_16 = (1LU << 16LU);
|
||||||
|
constexpr uint32_t CFG_ALT_SIZE_24 = (2LU << 16LU);
|
||||||
|
constexpr uint32_t CFG_ALT_SIZE_32 = (3LU << 16LU);
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_DATA_MODE_MASK = (3LU << 24LU);
|
||||||
|
constexpr uint32_t CFG_DATA_MODE_NONE = (0LU << 24LU);
|
||||||
|
constexpr uint32_t CFG_DATA_MODE_ONE_LINE = (1LU << 24LU);
|
||||||
|
constexpr uint32_t CFG_DATA_MODE_TWO_LINES = (2LU << 24LU);
|
||||||
|
constexpr uint32_t CFG_DATA_MODE_FOUR_LINES = (3LU << 24LU);
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_DATA_DDR = (1LU << 31LU);
|
||||||
|
|
||||||
|
constexpr uint32_t CFG_SIOO = (1LU << 28LU);
|
||||||
|
}
|
||||||
|
#endif //#if HAL_USE_QSPI_DEFAULT_CFG
|
||||||
|
|
||||||
|
class QSPIDevice : public Device
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
|
||||||
|
QSPIDevice() : Device(BUS_TYPE_QSPI) { }
|
||||||
|
|
||||||
|
/* See AP_HAL::Device::transfer() */
|
||||||
|
virtual bool transfer(const uint8_t *send, uint32_t send_len,
|
||||||
|
uint8_t *recv, uint32_t recv_len) override = 0;
|
||||||
|
|
||||||
|
// Set command header for upcomming transfer call(s)
|
||||||
|
virtual void set_cmd_header(const CommandHeader& cmd_hdr) override = 0;
|
||||||
|
|
||||||
|
virtual AP_HAL::Semaphore* get_semaphore() override = 0;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
uint32_t _trx_flags;
|
||||||
|
};
|
||||||
|
|
||||||
|
class QSPIDeviceManager
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
virtual OwnPtr<QSPIDevice> get_device(const char *name)
|
||||||
|
{
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Return the number of QSPI devices currently registered. */
|
||||||
|
virtual uint8_t get_count() const
|
||||||
|
{
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Get qspi device name at @idx */
|
||||||
|
virtual const char *get_device_name(uint8_t idx) const
|
||||||
|
{
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
Loading…
Reference in New Issue
Block a user