Merge pull request #6851 from jflyper/bfdev-refactor-spi-rx-to-use-spiBusXXX

RX SPI: Refactor rx_spi to use spiBusXXX API
This commit is contained in:
Michael Keller 2018-10-03 00:52:16 +13:00 committed by GitHub
commit f81bb550ba
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
10 changed files with 100 additions and 86 deletions

View File

@ -141,6 +141,18 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
}
}
uint8_t spiBusTransferByte(const busDevice_t *bus, uint8_t data)
{
return spiTransferByte(bus->busdev_u.spi.instance, data);
}
void spiBusWriteByte(const busDevice_t *bus, uint8_t data)
{
IOLo(bus->busdev_u.spi.csnPin);
spiBusTransferByte(bus, data);
IOHi(bus->busdev_u.spi.csnPin);
}
bool spiBusWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
{
IOLo(bus->busdev_u.spi.csnPin);
@ -151,27 +163,46 @@ bool spiBusWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
return true;
}
bool spiBusReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length)
bool spiBusRawReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length)
{
IOLo(bus->busdev_u.spi.csnPin);
spiTransferByte(bus->busdev_u.spi.instance, reg | 0x80); // read transaction
spiTransferByte(bus->busdev_u.spi.instance, reg);
spiTransfer(bus->busdev_u.spi.instance, NULL, data, length);
IOHi(bus->busdev_u.spi.csnPin);
return true;
}
uint8_t spiBusReadRegister(const busDevice_t *bus, uint8_t reg)
bool spiBusReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length)
{
return spiBusRawReadRegisterBuffer(bus, reg | 0x80, data, length);
}
void spiBusWriteRegisterBuffer(const busDevice_t *bus, uint8_t reg, const uint8_t *data, uint8_t length)
{
IOLo(bus->busdev_u.spi.csnPin);
spiTransferByte(bus->busdev_u.spi.instance, reg);
spiTransfer(bus->busdev_u.spi.instance, data, NULL, length);
IOHi(bus->busdev_u.spi.csnPin);
}
uint8_t spiBusRawReadRegister(const busDevice_t *bus, uint8_t reg)
{
uint8_t data;
IOLo(bus->busdev_u.spi.csnPin);
spiTransferByte(bus->busdev_u.spi.instance, reg | 0x80); // read transaction
spiTransferByte(bus->busdev_u.spi.instance, reg);
spiTransfer(bus->busdev_u.spi.instance, NULL, &data, 1);
IOHi(bus->busdev_u.spi.csnPin);
return data;
}
uint8_t spiBusReadRegister(const busDevice_t *bus, uint8_t reg)
{
return spiBusRawReadRegister(bus, reg | 0x80);
}
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance)
{
bus->bustype = BUSTYPE_SPI;

View File

@ -114,8 +114,14 @@ SPI_TypeDef *spiInstanceByDevice(SPIDevice device);
bool spiBusTransfer(const busDevice_t *bus, const uint8_t *txData, uint8_t *rxData, int length);
uint8_t spiBusTransferByte(const busDevice_t *bus, uint8_t data);
void spiBusWriteByte(const busDevice_t *bus, uint8_t data);
bool spiBusWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data);
bool spiBusRawReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length);
bool spiBusReadRegisterBuffer(const busDevice_t *bus, uint8_t reg, uint8_t *data, uint8_t length);
void spiBusWriteRegisterBuffer(const busDevice_t *bus, uint8_t reg, const uint8_t *data, uint8_t length);
uint8_t spiBusRawReadRegister(const busDevice_t *bus, uint8_t reg);
uint8_t spiBusReadRegister(const busDevice_t *bus, uint8_t reg);
void spiBusSetInstance(busDevice_t *bus, SPI_TypeDef *instance);

View File

@ -43,30 +43,28 @@
#define NOP 0xFF
uint8_t cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len)
void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len)
{
return rxSpiReadCommandMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, NOP, dpbuffer, len);
rxSpiReadCommandMulti(CC2500_3F_RXFIFO | CC2500_READ_BURST, NOP, dpbuffer, len);
}
uint8_t cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len)
void cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len)
{
uint8_t ret;
cc2500Strobe(CC2500_SFTX); // 0x3B SFTX
ret = rxSpiWriteCommandMulti(CC2500_3F_TXFIFO | CC2500_WRITE_BURST,
rxSpiWriteCommandMulti(CC2500_3F_TXFIFO | CC2500_WRITE_BURST,
dpbuffer, len);
cc2500Strobe(CC2500_STX); // 0x35
return ret;
}
uint8_t cc2500ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
void cc2500ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t length)
{
return rxSpiReadCommandMulti(address, NOP, data, length);
rxSpiReadCommandMulti(address, NOP, data, length);
}
uint8_t cc2500WriteRegisterMulti(uint8_t address, uint8_t *data,
void cc2500WriteRegisterMulti(uint8_t address, uint8_t *data,
uint8_t length)
{
return rxSpiWriteCommandMulti(address, data, length);
rxSpiWriteCommandMulti(address, data, length);
}
uint8_t cc2500ReadReg(uint8_t reg)
@ -76,9 +74,9 @@ uint8_t cc2500ReadReg(uint8_t reg)
void cc2500Strobe(uint8_t address) { rxSpiWriteByte(address); }
uint8_t cc2500WriteReg(uint8_t address, uint8_t data)
void cc2500WriteReg(uint8_t address, uint8_t data)
{
return rxSpiWriteCommand(address, data);
rxSpiWriteCommand(address, data);
}
void cc2500SetPower(uint8_t power)

View File

@ -157,16 +157,16 @@ enum {
#define CC2500_LQI_CRC_OK_BM 0x80
#define CC2500_LQI_EST_BM 0x7F
uint8_t cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len);
uint8_t cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len);
void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len);
void cc2500WriteFifo(uint8_t *dpbuffer, uint8_t len);
uint8_t cc2500ReadRegisterMulti(uint8_t address, uint8_t *data,
void cc2500ReadRegisterMulti(uint8_t address, uint8_t *data,
uint8_t length);
uint8_t cc2500WriteRegisterMulti(uint8_t address, uint8_t *data,
void cc2500WriteRegisterMulti(uint8_t address, uint8_t *data,
uint8_t length);
uint8_t cc2500ReadReg(uint8_t reg);
void cc2500Strobe(uint8_t address);
uint8_t cc2500WriteReg(uint8_t address, uint8_t data);
void cc2500WriteReg(uint8_t address, uint8_t data);
void cc2500SetPower(uint8_t power);
uint8_t cc2500Reset(void);

View File

@ -69,14 +69,14 @@ static void NRF24L01_InitGpio(void)
NRF24_CE_LO();
}
uint8_t NRF24L01_WriteReg(uint8_t reg, uint8_t data)
void NRF24L01_WriteReg(uint8_t reg, uint8_t data)
{
return rxSpiWriteCommand(W_REGISTER | (REGISTER_MASK & reg), data);
rxSpiWriteCommand(W_REGISTER | (REGISTER_MASK & reg), data);
}
uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length)
void NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length)
{
return rxSpiWriteCommandMulti(W_REGISTER | ( REGISTER_MASK & reg), data, length);
rxSpiWriteCommandMulti(W_REGISTER | ( REGISTER_MASK & reg), data, length);
}
/*
@ -84,14 +84,14 @@ uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t le
* Packets in the TX FIFO are transmitted when the
* nRF24L01 next enters TX mode
*/
uint8_t NRF24L01_WritePayload(const uint8_t *data, uint8_t length)
void NRF24L01_WritePayload(const uint8_t *data, uint8_t length)
{
return rxSpiWriteCommandMulti(W_TX_PAYLOAD, data, length);
rxSpiWriteCommandMulti(W_TX_PAYLOAD, data, length);
}
uint8_t NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe)
void NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe)
{
return rxSpiWriteCommandMulti(W_ACK_PAYLOAD | (pipe & 0x07), data, length);
rxSpiWriteCommandMulti(W_ACK_PAYLOAD | (pipe & 0x07), data, length);
}
uint8_t NRF24L01_ReadReg(uint8_t reg)
@ -99,17 +99,17 @@ uint8_t NRF24L01_ReadReg(uint8_t reg)
return rxSpiReadCommand(R_REGISTER | (REGISTER_MASK & reg), NOP);
}
uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length)
void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length)
{
return rxSpiReadCommandMulti(R_REGISTER | (REGISTER_MASK & reg), NOP, data, length);
rxSpiReadCommandMulti(R_REGISTER | (REGISTER_MASK & reg), NOP, data, length);
}
/*
* Read a packet from the nRF24L01 RX FIFO.
*/
uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
void NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
{
return rxSpiReadCommandMulti(R_RX_PAYLOAD, NOP, data, length);
rxSpiReadCommandMulti(R_RX_PAYLOAD, NOP, data, length);
}
/*
@ -128,9 +128,9 @@ void NRF24L01_FlushRx(void)
rxSpiWriteByte(FLUSH_RX);
}
uint8_t NRF24L01_Activate(uint8_t code)
void NRF24L01_Activate(uint8_t code)
{
return rxSpiWriteCommand(ACTIVATE, code);
rxSpiWriteCommand(ACTIVATE, code);
}
// standby configuration, used to simplify switching between RX, TX, and Standby modes

View File

@ -179,20 +179,20 @@ enum {
};
void NRF24L01_Initialize(uint8_t baseConfig);
uint8_t NRF24L01_WriteReg(uint8_t reg, uint8_t data);
uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length);
uint8_t NRF24L01_WritePayload(const uint8_t *data, uint8_t length);
uint8_t NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe);
void NRF24L01_WriteReg(uint8_t reg, uint8_t data);
void NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length);
void NRF24L01_WritePayload(const uint8_t *data, uint8_t length);
void NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe);
uint8_t NRF24L01_ReadReg(uint8_t reg);
uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length);
uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length);
void NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length);
void NRF24L01_ReadPayload(uint8_t *data, uint8_t length);
// Utility functions
void NRF24L01_FlushTx(void);
void NRF24L01_FlushRx(void);
uint8_t NRF24L01_Activate(uint8_t code);
void NRF24L01_Activate(uint8_t code);
void NRF24L01_SetupBasic(void);
void NRF24L01_SetStandbyMode(void);

View File

@ -41,12 +41,12 @@
#include "rx_spi.h"
#define ENABLE_RX() IOLo(busdev->busdev_u.spi.csnPin)
#define DISABLE_RX() IOHi(busdev->busdev_u.spi.csnPin)
static busDevice_t rxSpiDevice;
static busDevice_t *busdev = &rxSpiDevice;
#define DISABLE_RX() {IOHi(busdev->busdev_u.spi.csnPin);}
#define ENABLE_RX() {IOLo(busdev->busdev_u.spi.csnPin);}
bool rxSpiDeviceInit(const rxSpiConfig_t *rxSpiConfig)
{
if (!rxSpiConfig->spibus) {
@ -60,7 +60,7 @@ bool rxSpiDeviceInit(const rxSpiConfig_t *rxSpiConfig)
IOConfigGPIO(rxCsPin, SPI_IO_CS_CFG);
busdev->busdev_u.spi.csnPin = rxCsPin;
DISABLE_RX();
IOHi(rxCsPin);
spiSetDivisor(busdev->busdev_u.spi.instance, SPI_CLOCK_STANDARD);
@ -69,54 +69,33 @@ bool rxSpiDeviceInit(const rxSpiConfig_t *rxSpiConfig)
uint8_t rxSpiTransferByte(uint8_t data)
{
return spiTransferByte(busdev->busdev_u.spi.instance, data);
return spiBusTransferByte(busdev, data);
}
uint8_t rxSpiWriteByte(uint8_t data)
void rxSpiWriteByte(uint8_t data)
{
ENABLE_RX();
const uint8_t ret = rxSpiTransferByte(data);
DISABLE_RX();
return ret;
spiBusWriteByte(busdev, data);
}
uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data)
void rxSpiWriteCommand(uint8_t command, uint8_t data)
{
ENABLE_RX();
const uint8_t ret = rxSpiTransferByte(command);
rxSpiTransferByte(data);
DISABLE_RX();
return ret;
spiBusWriteRegister(busdev, command, data);
}
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length)
void rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length)
{
ENABLE_RX();
const uint8_t ret = rxSpiTransferByte(command);
for (uint8_t i = 0; i < length; i++) {
rxSpiTransferByte(data[i]);
}
DISABLE_RX();
return ret;
spiBusWriteRegisterBuffer(busdev, command, data, length);
}
uint8_t rxSpiReadCommand(uint8_t command, uint8_t data)
{
ENABLE_RX();
rxSpiTransferByte(command);
const uint8_t ret = rxSpiTransferByte(data);
DISABLE_RX();
return ret;
UNUSED(data);
return spiBusRawReadRegister(busdev, command);
}
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length)
void rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length)
{
ENABLE_RX();
const uint8_t ret = rxSpiTransferByte(command);
for (uint8_t i = 0; i < length; i++) {
retData[i] = rxSpiTransferByte(commandData);
}
DISABLE_RX();
return ret;
UNUSED(commandData);
spiBusRawReadRegisterBuffer(busdev, command, retData, length);
}
#endif

View File

@ -28,8 +28,8 @@ struct rxSpiConfig_s;
bool rxSpiDeviceInit(const struct rxSpiConfig_s *rxSpiConfig);
uint8_t rxSpiTransferByte(uint8_t data);
uint8_t rxSpiWriteByte(uint8_t data);
uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data);
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length);
void rxSpiWriteByte(uint8_t data);
void rxSpiWriteCommand(uint8_t command, uint8_t data);
void rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length);
uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData);
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length);
void rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length);

View File

@ -79,7 +79,7 @@ uint16_t XN297_UnscramblePayload(uint8_t *data, int len, const uint8_t *rxAddr)
return crc;
}
uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr)
void XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr)
{
uint8_t packet[NRF24L01_MAX_PAYLOAD_SIZE];
uint16_t crc = 0xb5d2;
@ -95,6 +95,6 @@ uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr)
crc ^= xn297_crc_xorout[len];
packet[RX_TX_ADDR_LEN + len] = crc >> 8;
packet[RX_TX_ADDR_LEN + len + 1] = crc & 0xff;
return NRF24L01_WritePayload(packet, RX_TX_ADDR_LEN + len + 2);
NRF24L01_WritePayload(packet, RX_TX_ADDR_LEN + len + 2);
}
#endif

View File

@ -24,4 +24,4 @@
#include <stdint.h>
uint16_t XN297_UnscramblePayload(uint8_t* data, int len, const uint8_t *rxAddr);
uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr);
void XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr);