its working

This commit is contained in:
Robin Müller 2021-06-10 21:31:21 +02:00
parent 1611099cb2
commit 621fe97d5d
No known key found for this signature in database
GPG Key ID: BE6480244DFE612C
11 changed files with 396 additions and 278 deletions

View File

@ -64,7 +64,9 @@ GyroL3GD20H::GyroL3GD20H(SPI_HandleTypeDef *spiHandle, spi::TransferModes transf
GyroL3GD20H::~GyroL3GD20H() {
delete txDmaHandle;
delete rxDmaHandle;
delete mspCfg;
if(mspCfg != nullptr) {
delete mspCfg;
}
}
ReturnValue_t GyroL3GD20H::initialize() {
@ -89,6 +91,7 @@ ReturnValue_t GyroL3GD20H::initialize() {
return HasReturnvaluesIF::RETURN_FAILED;
}
delete mspCfg;
transferState = TransferStates::WAIT;
sif::printInfo("GyroL3GD20H::performOperation: Reading WHO AM I register\n");

View File

@ -4,13 +4,13 @@
#include "fsfw/tasks/SemaphoreFactory.h"
#include "fsfw/osal/FreeRTOS/TaskManagement.h"
#include "fsfw_hal/stm32h7/spi/spiCore.h"
#include "fsfw_hal/stm32h7/spi/spiInterrupts.h"
#include "fsfw_hal/stm32h7/spi/mspInit.h"
#include "fsfw_hal/stm32h7/gpio/gpio.h"
#include "stm32h7xx_hal_gpio.h"
SpiComIF::SpiComIF(object_id_t objectId, spi::TransferModes transferMode):
SystemObject(objectId), transferMode(transferMode) {
SpiComIF::SpiComIF(object_id_t objectId): SystemObject(objectId) {
spi::assignTransferRxTxCompleteCallback(&spiTransferCompleteCallback, this);
spi::assignTransferRxCompleteCallback(&spiTransferRxCompleteCallback, this);
spi::assignTransferTxCompleteCallback(&spiTransferTxCompleteCallback, this);
@ -26,16 +26,6 @@ void SpiComIF::addDmaHandles(DMA_HandleTypeDef *txHandle, DMA_HandleTypeDef *rxH
}
ReturnValue_t SpiComIF::initialize() {
if(transferMode == spi::TransferModes::DMA) {
DMA_HandleTypeDef *txHandle = nullptr;
DMA_HandleTypeDef *rxHandle = nullptr;
spi::getDmaHandles(&txHandle, &rxHandle);
if(txHandle == nullptr or rxHandle == nullptr) {
sif::printError("SpiComIF::initialize: DMA handles not set!\n");
return HasReturnvaluesIF::RETURN_FAILED;
}
}
return HasReturnvaluesIF::RETURN_OK;
}
@ -49,15 +39,20 @@ ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) {
#endif
return NULLPOINTER;
}
auto transferMode = spiCookie->getTransferMode();
if(transferMode == spi::TransferModes::DMA or transferMode == spi::TransferModes::INTERRUPT) {
spiSemaphore = dynamic_cast<BinarySemaphore*>(
SemaphoreFactory::instance()->createBinarySemaphore());
if(transferMode == spi::TransferModes::DMA) {
DMA_HandleTypeDef *txHandle = nullptr;
DMA_HandleTypeDef *rxHandle = nullptr;
spi::getDmaHandles(&txHandle, &rxHandle);
if(txHandle == nullptr or rxHandle == nullptr) {
sif::printError("SpiComIF::initialize: DMA handles not set!\n");
return HasReturnvaluesIF::RETURN_FAILED;
}
}
else {
spiMutex = MutexFactory::instance()->createMutex();
}
// This semaphore ensures thread-safety for a given bus
spiSemaphore = dynamic_cast<BinarySemaphore*>(
SemaphoreFactory::instance()->createBinarySemaphore());
address_t spiAddress = spiCookie->getDeviceAddress();
auto iter = spiDeviceMap.find(spiAddress);
@ -82,17 +77,55 @@ ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) {
SPI_HandleTypeDef& spiHandle = spiCookie->getSpiHandle();
auto spiIdx = spiCookie->getSpiIdx();
if(spiIdx == spi::SpiBus::SPI_1) {
#ifdef SPI1
spiHandle.Instance = SPI1;
#endif
}
else if(spiIdx == spi::SpiBus::SPI_2) {
#ifdef SPI2
spiHandle.Instance = SPI2;
#endif
}
else {
printCfgError("SPI Bus Index");
return HasReturnvaluesIF::RETURN_FAILED;
}
auto mspCfg = spiCookie->getMspCfg();
if(transferMode == spi::TransferModes::POLLING) {
// spi::setSpiMspFunctions(&spi::halMspInitPolling, &spiHandle,
// &spi::halMspDeinitPolling, &spiHandle);
auto typedCfg = dynamic_cast<spi::MspPollingConfigStruct*>(mspCfg);
if(typedCfg == nullptr) {
printCfgError("Polling MSP");
return HasReturnvaluesIF::RETURN_FAILED;
}
spi::setSpiPollingMspFunctions(typedCfg);
}
else if(transferMode == spi::TransferModes::INTERRUPT) {
// spi::setSpiMspFunctions(&spi::halMspInitInterrupt, &spiHandle,
// &spi::halMspDeinitPolling, &spiHandle);
auto typedCfg = dynamic_cast<spi::MspIrqConfigStruct*>(mspCfg);
if(typedCfg == nullptr) {
printCfgError("IRQ MSP");
return HasReturnvaluesIF::RETURN_FAILED;
}
spi::setSpiIrqMspFunctions(typedCfg);
}
else if(transferMode == spi::TransferModes::DMA) {
// spi::setSpiMspFunctions(&spi::halMspInitDma, &spiHandle,
// &spi::halMspDeinitDma, &spiHandle);
auto typedCfg = dynamic_cast<spi::MspDmaConfigStruct*>(mspCfg);
if(typedCfg == nullptr) {
printCfgError("DMA MSP");
return HasReturnvaluesIF::RETURN_FAILED;
}
// Check DMA handles
DMA_HandleTypeDef* txHandle = nullptr;
DMA_HandleTypeDef* rxHandle = nullptr;
spi::getDmaHandles(&txHandle, &rxHandle);
if(txHandle == nullptr or rxHandle == nullptr) {
printCfgError("DMA Handle");
return HasReturnvaluesIF::RETURN_FAILED;
}
spi::setSpiDmaMspFunctions(typedCfg);
}
gpio::initializeGpioClock(gpioPort);
@ -106,6 +139,9 @@ ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) {
sif::printWarning("SpiComIF::initialize: Error initializing SPI\n");
return HasReturnvaluesIF::RETURN_FAILED;
}
// The MSP configuration struct is not required anymore
spiCookie->deleteMspCfg();
return HasReturnvaluesIF::RETURN_OK;
}
@ -123,6 +159,8 @@ ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, s
}
iter->second.currentTransferLen = sendLen;
auto transferMode = spiCookie->getTransferMode();
switch(transferMode) {
case(spi::TransferModes::POLLING): {
return handlePollingSendOperation(iter->second.replyBuffer.data(), spiHandle, *spiCookie,
@ -170,12 +208,15 @@ ReturnValue_t SpiComIF::handlePollingSendOperation(uint8_t* recvPtr, SPI_HandleT
SpiCookie& spiCookie, const uint8_t *sendData, size_t sendLen) {
auto gpioPort = spiCookie.getChipSelectGpioPort();
auto gpioPin = spiCookie.getChipSelectGpioPin();
spiMutex->lockMutex(timeoutType, timeoutMs);
auto returnval = spiSemaphore->acquire(timeoutType, timeoutMs);
if(returnval != HasReturnvaluesIF::RETURN_OK) {
return returnval;
}
HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_RESET);
auto result = HAL_SPI_TransmitReceive(&spiHandle, const_cast<uint8_t*>(sendData),
recvPtr, sendLen, defaultPollingTimeout);
HAL_GPIO_WritePin(gpioPort, gpioPin, GPIO_PIN_SET);
spiMutex->unlockMutex();
spiSemaphore->release();
switch(result) {
case(HAL_OK): {
break;
@ -227,6 +268,7 @@ ReturnValue_t SpiComIF::handleIrqSendOperation(uint8_t *recvPtr, SPI_HandleTypeD
}
// yet another HAL driver which is not const-correct..
HAL_StatusTypeDef status = HAL_OK;
auto transferMode = spiCookie.getTransferMode();
if(transferMode == spi::TransferModes::DMA) {
if(cacheMaintenanceOnTxBuffer) {
/* Clean D-cache. Make sure the address is 32-byte aligned and add 32-bytes to length,
@ -246,13 +288,13 @@ ReturnValue_t SpiComIF::handleIrqSendOperation(uint8_t *recvPtr, SPI_HandleTypeD
break;
}
default: {
return halErrorHandler(status);
return halErrorHandler(status, transferMode);
}
}
return result;
}
ReturnValue_t SpiComIF::halErrorHandler(HAL_StatusTypeDef status) {
ReturnValue_t SpiComIF::halErrorHandler(HAL_StatusTypeDef status, spi::TransferModes transferMode) {
char modeString[10];
if(transferMode == spi::TransferModes::DMA) {
std::snprintf(modeString, sizeof(modeString), "Dma");
@ -291,10 +333,14 @@ ReturnValue_t SpiComIF::genericIrqSendSetup(uint8_t *recvPtr, SPI_HandleTypeDef&
ReturnValue_t result = spiSemaphore->acquire(SemaphoreIF::TimeoutType::WAITING, timeoutMs);
if(result != HasReturnvaluesIF::RETURN_OK) {
// Configuration error
sif::printWarning("SpiComIF::handleInterruptSendOperation: Semaphore"
sif::printWarning("SpiComIF::handleInterruptSendOperation: Semaphore "
"could not be acquired after %d ms\n", timeoutMs);
return result;
}
// Cache the current SPI handle in any case
spi::setSpiHandle(&spiHandle);
// The SPI handle is passed to the default SPI callback as a void argument
spi::assignSpiUserArgs(spiCookie.getSpiIdx(), reinterpret_cast<void*>(&spiHandle));
HAL_GPIO_WritePin(currentGpioPort, currentGpioPin, GPIO_PIN_RESET);
return HasReturnvaluesIF::RETURN_OK;
}
@ -341,13 +387,13 @@ void SpiComIF::genericIrqHandler(SpiComIF *spiComIF, TransferStates targetState)
BaseType_t taskWoken = pdFALSE;
ReturnValue_t result = BinarySemaphore::releaseFromISR(spiComIF->spiSemaphore->getSemaphore(),
&taskWoken);
if(result != HasReturnvaluesIF::RETURN_FAILED) {
if(result != HasReturnvaluesIF::RETURN_OK) {
// Configuration error
printf("SpiComIF::genericIrqHandler: Failure releasing Semaphore!\n");
}
// Perform cache maintenance operation for DMA transfers
if(spiComIF->transferMode == spi::TransferModes::DMA) {
if(spiComIF->currentTransferMode == spi::TransferModes::DMA) {
// Invalidate cache prior to access by CPU
SCB_InvalidateDCache_by_Addr ((uint32_t *) spiComIF->currentRecvPtr,
spiComIF->currentRecvBuffSize);
@ -358,3 +404,12 @@ void SpiComIF::genericIrqHandler(SpiComIF *spiComIF, TransferStates targetState)
TaskManagement::requestContextSwitch(CallContext::ISR);
}
}
void SpiComIF::printCfgError(const char *const type) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "SpiComIF::initializeInterface: Invalid " << type << " configuration"
<< std::endl;
#else
sif::printWarning("SpiComIF::initializeInterface: Invalid %s configuration\n", type);
#endif
}

View File

@ -1,8 +1,6 @@
#ifndef FSFW_HAL_STM32H7_SPI_SPICOMIF_H_
#define FSFW_HAL_STM32H7_SPI_SPICOMIF_H_
#include "fsfw/tasks/SemaphoreIF.h"
#include "fsfw/devicehandlers/DeviceCommunicationIF.h"
#include "fsfw/objectmanager/SystemObject.h"
@ -24,6 +22,19 @@ enum class TransferStates {
FAILURE
};
/**
* @brief This communication interface allows using generic device handlers with using
* the STM32H7 SPI peripherals
* @details
* This communication interface supports all three major communcation modes:
* - Polling: Simple, but not recommended to real use-cases, blocks the CPU
* - Interrupt: Good for small data only arriving occasionally
* - DMA: Good for large data which also occur regularly. Please note that the number
* of DMA channels in limited
* The device specific information is usually kept in the SpiCookie class. The current
* implementation limits the transfer mode for a given SPI bus.
* @author R. Mueller
*/
class SpiComIF:
public SystemObject,
public DeviceCommunicationIF {
@ -35,7 +46,7 @@ public:
* @param spiHandle
* @param transferMode
*/
SpiComIF(object_id_t objectId, spi::TransferModes transferMode);
SpiComIF(object_id_t objectId);
/**
* Allows the user to disable cache maintenance on the TX buffer. This can be done if the
@ -49,7 +60,7 @@ public:
void setDefaultPollingTimeout(dur_millis_t timeout);
/**
* Add the DMA handles. These need to be set in the DMA transfer mode is used
* Add the DMA handles. These need to be set in the DMA transfer mode is used.
* @param txHandle
* @param rxHandle
*/
@ -68,7 +79,6 @@ protected:
virtual ReturnValue_t readReceivedMessage(CookieIF *cookie,
uint8_t **buffer, size_t *size) override;
private:
struct SpiInstance {
@ -79,13 +89,11 @@ private:
uint32_t defaultPollingTimeout = 50;
spi::TransferModes transferMode;
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
SemaphoreIF::TimeoutType timeoutType = SemaphoreIF::TimeoutType::WAITING;
dur_millis_t timeoutMs = 20;
spi::TransferModes currentTransferMode = spi::TransferModes::POLLING;
BinarySemaphore* spiSemaphore = nullptr;
MutexIF* spiMutex = nullptr;
bool cacheMaintenanceOnTxBuffer = true;
using SpiDeviceMap = std::map<address_t, SpiInstance>;
@ -109,7 +117,7 @@ private:
SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen);
ReturnValue_t genericIrqSendSetup(uint8_t* recvPtr, SPI_HandleTypeDef& spiHandle,
SpiCookie& spiCookie, const uint8_t * sendData, size_t sendLen);
ReturnValue_t halErrorHandler(HAL_StatusTypeDef status);
ReturnValue_t halErrorHandler(HAL_StatusTypeDef status, spi::TransferModes transferMode);
static void spiTransferTxCompleteCallback(SPI_HandleTypeDef *hspi, void* args);
static void spiTransferRxCompleteCallback(SPI_HandleTypeDef *hspi, void* args);
@ -118,7 +126,7 @@ private:
static void genericIrqHandler(SpiComIF* comIF, TransferStates targetState);
void printCfgError(const char* const type);
};

View File

@ -1,13 +1,12 @@
#include "SpiCookie.h"
SpiCookie::SpiCookie(address_t deviceAddress, spi::SpiBus spiIdx, SPI_TypeDef* spiInstance,
uint32_t spiSpeed, spi::SpiModes spiMode, uint16_t chipSelectGpioPin,
GPIO_TypeDef* chipSelectGpioPort, size_t maxRecvSize):
deviceAddress(deviceAddress), spiIdx(spiIdx), spiSpeed(spiSpeed), spiMode(spiMode),
chipSelectGpioPin(chipSelectGpioPin), chipSelectGpioPort(chipSelectGpioPort),
maxRecvSize(maxRecvSize) {
spiHandle.Instance = spiInstance;
SpiCookie::SpiCookie(address_t deviceAddress, spi::SpiBus spiIdx, spi::TransferModes transferMode,
spi::MspCfgBase* mspCfg, uint32_t spiSpeed, spi::SpiModes spiMode,
uint16_t chipSelectGpioPin, GPIO_TypeDef* chipSelectGpioPort, size_t maxRecvSize):
deviceAddress(deviceAddress), spiIdx(spiIdx), transferMode(transferMode),
spiSpeed(spiSpeed), spiMode(spiMode), chipSelectGpioPin(chipSelectGpioPin),
chipSelectGpioPort(chipSelectGpioPort), mspCfg(mspCfg), maxRecvSize(maxRecvSize) {
spiHandle.Init.DataSize = SPI_DATASIZE_8BIT;
spiHandle.Init.FirstBit = SPI_FIRSTBIT_MSB;
spiHandle.Init.TIMode = SPI_TIMODE_DISABLE;
@ -55,3 +54,17 @@ size_t SpiCookie::getMaxRecvSize() const {
SPI_HandleTypeDef& SpiCookie::getSpiHandle() {
return spiHandle;
}
spi::MspCfgBase* SpiCookie::getMspCfg() {
return mspCfg;
}
void SpiCookie::deleteMspCfg() {
if(mspCfg != nullptr) {
delete mspCfg;
}
}
spi::TransferModes SpiCookie::getTransferMode() const {
return transferMode;
}

View File

@ -2,15 +2,39 @@
#define FSFW_HAL_STM32H7_SPI_SPICOOKIE_H_
#include "spiDefinitions.h"
#include "mspInit.h"
#include "fsfw/devicehandlers/CookieIF.h"
#include "stm32h743xx.h"
/**
* @brief SPI cookie implementation for the STM32H7 device family
* @details
* This cookie contains and caches device specific information to be used by the
* SPI communication interface
* @author R. Mueller
*/
class SpiCookie: public CookieIF {
friend class SpiComIF;
public:
SpiCookie(address_t deviceAddress, spi::SpiBus spiIdx, SPI_TypeDef* spiInstance,
uint32_t spiSpeed, spi::SpiModes spiMode,
/**
* Allows construction of a SPI cookie for a connected SPI device
* @param deviceAddress
* @param spiIdx SPI bus, e.g. SPI1 or SPI2
* @param transferMode
* @param mspCfg This is the MSP configuration. The user is expected to supply
* a valid MSP configuration. See mspInit.h for functions
* to create one.
* @param spiSpeed
* @param spiMode
* @param chipSelectGpioPin GPIO port. Don't use a number here, use the 16 bit type
* definitions supplied in the MCU header file! (e.g. GPIO_PIN_X)
* @param chipSelectGpioPort GPIO port (e.g. GPIOA)
* @param maxRecvSize Maximum expected receive size. Chose as small as possible.
*/
SpiCookie(address_t deviceAddress, spi::SpiBus spiIdx, spi::TransferModes transferMode,
spi::MspCfgBase* mspCfg, uint32_t spiSpeed, spi::SpiModes spiMode,
uint16_t chipSelectGpioPin, GPIO_TypeDef* chipSelectGpioPort, size_t maxRecvSize);
uint16_t getChipSelectGpioPin() const;
@ -18,6 +42,7 @@ public:
address_t getDeviceAddress() const;
spi::SpiBus getSpiIdx() const;
spi::SpiModes getSpiMode() const;
spi::TransferModes getTransferMode() const;
uint32_t getSpiSpeed() const;
size_t getMaxRecvSize() const;
SPI_HandleTypeDef& getSpiHandle();
@ -28,9 +53,17 @@ private:
spi::SpiBus spiIdx;
uint32_t spiSpeed;
spi::SpiModes spiMode;
spi::TransferModes transferMode;
uint16_t chipSelectGpioPin;
GPIO_TypeDef* chipSelectGpioPort;
// The MSP configuration is cached here. Be careful when using this, it is automatically
// deleted by the SPI communication interface if it is not required anymore!
spi::MspCfgBase* mspCfg = nullptr;
const size_t maxRecvSize;
// Only the SpiComIF is allowed to use this to prevent dangling pointers issues
spi::MspCfgBase* getMspCfg();
void deleteMspCfg();
};

View File

@ -36,7 +36,7 @@ void spi::halMspInitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) {
DMA_HandleTypeDef* hdma_tx = nullptr;
DMA_HandleTypeDef* hdma_rx = nullptr;
spi::getDmaHandles(&hdma_tx, &hdma_rx);
if(hdma_tx == NULL || hdma_rx == NULL) {
if(hdma_tx == nullptr or hdma_rx == nullptr) {
printf("HAL_SPI_MspInit: Invalid DMA handles. Make sure to call setDmaHandles!\n");
return;
}
@ -55,46 +55,12 @@ void spi::halMspInitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) {
// Assume it was not configured properly
mspErrorHandler("spi::halMspInitDma", "DMA TX handle invalid");
}
hdma_tx->Instance = SPIx_TX_DMA_STREAM;
hdma_tx->Init.Request = SPIx_TX_DMA_REQUEST;
// offer function to configure this..
hdma_tx->Init.FIFOMode = DMA_FIFOMODE_DISABLE;
hdma_tx->Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
hdma_tx->Init.MemBurst = DMA_MBURST_INC4;
hdma_tx->Init.PeriphBurst = DMA_PBURST_INC4;
hdma_tx->Init.Direction = DMA_MEMORY_TO_PERIPH;
hdma_tx->Init.PeriphInc = DMA_PINC_DISABLE;
hdma_tx->Init.MemInc = DMA_MINC_ENABLE;
hdma_tx->Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_tx->Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_tx->Init.Mode = DMA_NORMAL;
hdma_tx->Init.Priority = DMA_PRIORITY_LOW;
HAL_DMA_Init(hdma_tx);
/* Associate the initialized DMA handle to the the SPI handle */
__HAL_LINKDMA(hspi, hdmatx, *hdma_tx);
/* Configure the DMA handler for Transmission process */
hdma_rx->Instance = SPIx_RX_DMA_STREAM;
hdma_rx->Init.FIFOMode = DMA_FIFOMODE_DISABLE;
hdma_rx->Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL;
hdma_rx->Init.MemBurst = DMA_MBURST_INC4;
hdma_rx->Init.PeriphBurst = DMA_PBURST_INC4;
hdma_rx->Init.Request = SPIx_RX_DMA_REQUEST;
hdma_rx->Init.Direction = DMA_PERIPH_TO_MEMORY;
hdma_rx->Init.PeriphInc = DMA_PINC_DISABLE;
hdma_rx->Init.MemInc = DMA_MINC_ENABLE;
hdma_rx->Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
hdma_rx->Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
hdma_rx->Init.Mode = DMA_NORMAL;
hdma_rx->Init.Priority = DMA_PRIORITY_HIGH;
HAL_DMA_Init(hdma_rx);
/* Associate the initialized DMA handle to the the SPI handle */
__HAL_LINKDMA(hspi, hdmarx, *hdma_rx);
@ -111,14 +77,6 @@ void spi::halMspInitDma(SPI_HandleTypeDef* hspi, MspCfgBase* cfgBase) {
&spi::dmaTxIrqHandler, hdma_tx);
HAL_NVIC_SetPriority(cfg->txDmaIrqNumber, cfg->txPreEmptPriority, cfg->txSubpriority);
HAL_NVIC_EnableIRQ(cfg->txDmaIrqNumber);
/*##-5- Configure the NVIC for SPI #########################################*/
/* NVIC configuration for SPI transfer complete interrupt (SPI1) */
// Assign the interrupt handler
spi::assignSpiUserHandler(spi::SPI_1, &spi::spiIrqHandler, hspi);
HAL_NVIC_SetPriority(SPIx_IRQn, 1, 0);
HAL_NVIC_EnableIRQ(SPIx_IRQn);
}
/**

View File

@ -3,6 +3,7 @@
#include "spiDefinitions.h"
#include "../dma.h"
#include "stm32h7xx_hal_spi.h"
#include <cstdint>
@ -11,6 +12,10 @@
extern "C" {
#endif
/**
* @brief This file provides MSP implementation for DMA, IRQ and Polling mode for the
* SPI peripheral. This configuration is required for the SPI communication to work.
*/
namespace spi {
struct MspCfgBase {

View File

@ -1,3 +1,4 @@
#include "spiDefinitions.h"
#include "spiCore.h"
#include <cstdio>
@ -14,178 +15,16 @@ void* rxArgs = nullptr;
spi_transfer_cb_t errorCb = nullptr;
void* errorArgs = nullptr;
void spi::configureDmaHandle(DMA_HandleTypeDef *handle, dma::DMAType dmaType,
void mapIndexAndStream(DMA_HandleTypeDef* handle, dma::DMAType dmaType, dma::DMAIndexes dmaIdx,
dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber);
void mapSpiBus(DMA_HandleTypeDef *handle, dma::DMAType dmaType, spi::SpiBus spiBus);
void spi::configureDmaHandle(DMA_HandleTypeDef *handle, spi::SpiBus spiBus, dma::DMAType dmaType,
dma::DMAIndexes dmaIdx, dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber,
uint32_t dmaMode, uint32_t dmaPriority) {
using namespace dma;
if(dmaIdx == DMAIndexes::DMA_1) {
#ifdef DMA1
switch(dmaStream) {
case(DMAStreams::STREAM_0): {
#ifdef DMA1_Stream0
handle->Instance = DMA1_Stream0;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream0_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_1): {
#ifdef DMA1_Stream1
handle->Instance = DMA1_Stream1;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream1_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_2): {
#ifdef DMA1_Stream2
handle->Instance = DMA1_Stream2;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream2_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_3): {
#ifdef DMA1_Stream3
handle->Instance = DMA1_Stream3;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream3_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_4): {
#ifdef DMA1_Stream4
handle->Instance = DMA1_Stream4;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream4_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_5): {
#ifdef DMA1_Stream5
handle->Instance = DMA1_Stream5;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream5_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_6): {
#ifdef DMA1_Stream6
handle->Instance = DMA1_Stream6;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream6_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_7): {
#ifdef DMA1_Stream7
handle->Instance = DMA1_Stream7;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream7_IRQn;
}
#endif
break;
}
}
if(dmaType == DMAType::TX) {
handle->Init.Request = DMA_REQUEST_SPI1_TX;
}
else {
handle->Init.Request = DMA_REQUEST_SPI1_RX;
}
#endif /* DMA1 */
}
if(dmaIdx == DMAIndexes::DMA_2) {
#ifdef DMA2
switch(dmaStream) {
case(DMAStreams::STREAM_0): {
#ifdef DMA1_Stream0
handle->Instance = DMA2_Stream0;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream0_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_1): {
#ifdef DMA1_Stream1
handle->Instance = DMA2_Stream1;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream1_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_2): {
#ifdef DMA1_Stream2
handle->Instance = DMA2_Stream2;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream2_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_3): {
#ifdef DMA1_Stream3
handle->Instance = DMA2_Stream3;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream3_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_4): {
#ifdef DMA1_Stream4
handle->Instance = DMA1_Stream4;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream4_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_5): {
#ifdef DMA1_Stream5
handle->Instance = DMA1_Stream5;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream5_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_6): {
#ifdef DMA1_Stream6
handle->Instance = DMA1_Stream6;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream6_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_7): {
#ifdef DMA1_Stream7
handle->Instance = DMA1_Stream7;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream7_IRQn;
}
#endif
break;
}
}
if(dmaType == DMAType::TX) {
handle->Init.Request = DMA_REQUEST_SPI2_TX;
}
else {
handle->Init.Request = DMA_REQUEST_SPI2_RX;
}
#endif /* DMA2 */
}
mapIndexAndStream(handle, dmaType, dmaIdx, dmaStream, dmaIrqNumber);
mapSpiBus(handle, dmaType, spiBus);
if(dmaType == DMAType::TX) {
handle->Init.Direction = DMA_MEMORY_TO_PERIPH;
@ -305,3 +144,197 @@ extern "C" void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi) {
printf("HAL_SPI_ErrorCallback: No user callback specified\n");
}
}
void mapIndexAndStream(DMA_HandleTypeDef* handle, dma::DMAType dmaType, dma::DMAIndexes dmaIdx,
dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber) {
using namespace dma;
if(dmaIdx == DMAIndexes::DMA_1) {
#ifdef DMA1
switch(dmaStream) {
case(DMAStreams::STREAM_0): {
#ifdef DMA1_Stream0
handle->Instance = DMA1_Stream0;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream0_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_1): {
#ifdef DMA1_Stream1
handle->Instance = DMA1_Stream1;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream1_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_2): {
#ifdef DMA1_Stream2
handle->Instance = DMA1_Stream2;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream2_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_3): {
#ifdef DMA1_Stream3
handle->Instance = DMA1_Stream3;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream3_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_4): {
#ifdef DMA1_Stream4
handle->Instance = DMA1_Stream4;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream4_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_5): {
#ifdef DMA1_Stream5
handle->Instance = DMA1_Stream5;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream5_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_6): {
#ifdef DMA1_Stream6
handle->Instance = DMA1_Stream6;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream6_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_7): {
#ifdef DMA1_Stream7
handle->Instance = DMA1_Stream7;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA1_Stream7_IRQn;
}
#endif
break;
}
}
if(dmaType == DMAType::TX) {
handle->Init.Request = DMA_REQUEST_SPI1_TX;
}
else {
handle->Init.Request = DMA_REQUEST_SPI1_RX;
}
#endif /* DMA1 */
}
if(dmaIdx == DMAIndexes::DMA_2) {
#ifdef DMA2
switch(dmaStream) {
case(DMAStreams::STREAM_0): {
#ifdef DMA2_Stream0
handle->Instance = DMA2_Stream0;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream0_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_1): {
#ifdef DMA2_Stream1
handle->Instance = DMA2_Stream1;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream1_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_2): {
#ifdef DMA2_Stream2
handle->Instance = DMA2_Stream2;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream2_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_3): {
#ifdef DMA2_Stream3
handle->Instance = DMA2_Stream3;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream3_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_4): {
#ifdef DMA2_Stream4
handle->Instance = DMA2_Stream4;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream4_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_5): {
#ifdef DMA2_Stream5
handle->Instance = DMA2_Stream5;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream5_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_6): {
#ifdef DMA2_Stream6
handle->Instance = DMA2_Stream6;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream6_IRQn;
}
#endif
break;
}
case(DMAStreams::STREAM_7): {
#ifdef DMA2_Stream7
handle->Instance = DMA2_Stream7;
if(dmaIrqNumber != nullptr) {
*dmaIrqNumber = DMA2_Stream7_IRQn;
}
#endif
break;
}
}
#endif /* DMA2 */
}
}
void mapSpiBus(DMA_HandleTypeDef *handle, dma::DMAType dmaType, spi::SpiBus spiBus) {
if(dmaType == dma::DMAType::TX) {
if(spiBus == spi::SpiBus::SPI_1) {
#ifdef DMA_REQUEST_SPI1_TX
handle->Init.Request = DMA_REQUEST_SPI1_TX;
#endif
}
else if(spiBus == spi::SpiBus::SPI_2) {
#ifdef DMA_REQUEST_SPI2_TX
handle->Init.Request = DMA_REQUEST_SPI2_TX;
#endif
}
}
else {
if(spiBus == spi::SpiBus::SPI_1) {
#ifdef DMA_REQUEST_SPI1_RX
handle->Init.Request = DMA_REQUEST_SPI1_RX;
#endif
}
else if(spiBus == spi::SpiBus::SPI_2) {
#ifdef DMA_REQUEST_SPI2_RX
handle->Init.Request = DMA_REQUEST_SPI2_RX;
#endif
}
}
}

View File

@ -14,7 +14,8 @@ using spi_transfer_cb_t = void (*) (SPI_HandleTypeDef *hspi, void* userArgs);
namespace spi {
void configureDmaHandle(DMA_HandleTypeDef* Handle, dma::DMAType dmaType, dma::DMAIndexes dmaIdx,
void configureDmaHandle(DMA_HandleTypeDef* handle, spi::SpiBus spiBus,
dma::DMAType dmaType, dma::DMAIndexes dmaIdx,
dma::DMAStreams dmaStream, IRQn_Type* dmaIrqNumber, uint32_t dmaMode = DMA_NORMAL,
uint32_t dmaPriority = DMA_PRIORITY_LOW);

View File

@ -19,6 +19,9 @@ user_args_t spi2UserArgs = nullptr;
* @retval None
*/
void spi::dmaRxIrqHandler(void* dmaHandle) {
if(dmaHandle == nullptr) {
return;
}
HAL_DMA_IRQHandler((DMA_HandleTypeDef *) dmaHandle);
}
@ -28,6 +31,9 @@ void spi::dmaRxIrqHandler(void* dmaHandle) {
* @retval None
*/
void spi::dmaTxIrqHandler(void* dmaHandle) {
if(dmaHandle == nullptr) {
return;
}
HAL_DMA_IRQHandler((DMA_HandleTypeDef *) dmaHandle);
}
@ -38,8 +44,11 @@ void spi::dmaTxIrqHandler(void* dmaHandle) {
*/
void spi::spiIrqHandler(void* spiHandle)
{
auto currentSpiHandle = spi::getSpiHandle();
HAL_SPI_IRQHandler((SPI_HandleTypeDef *) currentSpiHandle);
if(spiHandle == nullptr) {
return;
}
//auto currentSpiHandle = spi::getSpiHandle();
HAL_SPI_IRQHandler((SPI_HandleTypeDef *) spiHandle);
}
void spi::assignSpiUserHandler(spi::SpiBus spiIdx, user_handler_t userHandler,
@ -69,7 +78,7 @@ void spi::getSpiUserHandler(spi::SpiBus spiBus, user_handler_t *userHandler,
}
}
void assignSpiUserArgs(spi::SpiBus spiBus, user_args_t userArgs) {
void spi::assignSpiUserArgs(spi::SpiBus spiBus, user_args_t userArgs) {
if(spiBus == spi::SpiBus::SPI_1) {
spi1UserArgs = userArgs;
}

View File

@ -18,7 +18,7 @@ void spiCleanUpWrapper() {
}
void spiDmaClockEnableWrapper() {
__HAL_RCC_SPI1_CLK_ENABLE();
__HAL_RCC_DMA2_CLK_ENABLE();
}
void spi::h743zi::standardPollingCfg(MspPollingConfigStruct& cfg) {
@ -55,24 +55,24 @@ void spi::h743zi::standardInterruptCfg(MspIrqConfigStruct& cfg, IrqPriorities sp
}
void spi::h743zi::standardDmaCfg(MspDmaConfigStruct& cfg, IrqPriorities spiIrqPrio,
IrqPriorities txIrqPrio, IrqPriorities rxIrqPrio, IrqPriorities spiSubprio,
IrqPriorities txIrqPrio, IrqPriorities rxIrqPrio, IrqPriorities spiSubprio,
IrqPriorities txSubprio, IrqPriorities rxSubprio) {
cfg.dmaClkEnableWrapper = &spiDmaClockEnableWrapper;
cfg.rxDmaIndex = dma::DMAIndexes::DMA_1;
cfg.txDmaIndex = dma::DMAIndexes::DMA_1;
cfg.rxDmaIndex = dma::DMAIndexes::DMA_2;
cfg.txDmaIndex = dma::DMAIndexes::DMA_2;
cfg.txDmaStream = dma::DMAStreams::STREAM_3;
cfg.rxDmaStream = dma::DMAStreams::STREAM_2;
DMA_HandleTypeDef* txHandle;
DMA_HandleTypeDef* rxHandle;
spi::getDmaHandles(&txHandle, &rxHandle);
if(txHandle == nullptr or rxHandle == nullptr) {
printf("spi::h743zi::standardDmaCfg: Invalid DMA handles");
printf("spi::h743zi::standardDmaCfg: Invalid DMA handles\n");
return;
}
spi::configureDmaHandle(txHandle, dma::DMAType::TX, cfg.txDmaIndex, cfg.txDmaStream,
&cfg.txDmaIrqNumber);
spi::configureDmaHandle(rxHandle, dma::DMAType::RX, cfg.rxDmaIndex, cfg.rxDmaStream,
&cfg.rxDmaIrqNumber);
spi::configureDmaHandle(txHandle, spi::SpiBus::SPI_1, dma::DMAType::TX, cfg.txDmaIndex,
cfg.txDmaStream, &cfg.txDmaIrqNumber);
spi::configureDmaHandle(rxHandle, spi::SpiBus::SPI_1, dma::DMAType::RX, cfg.rxDmaIndex,
cfg.rxDmaStream, &cfg.rxDmaIrqNumber, DMA_NORMAL, DMA_PRIORITY_HIGH);
cfg.txPreEmptPriority = txIrqPrio;
cfg.rxPreEmptPriority = txSubprio;
cfg.txSubpriority = rxIrqPrio;