[H7] Add USE_DMA_SPEC to H7

This commit is contained in:
jflyper 2019-06-06 01:35:44 +09:00
parent c6041e1ed6
commit 16f2392458
8 changed files with 247 additions and 23 deletions

View File

@ -648,7 +648,7 @@ static const char *dumpPgValue(const clivalue_t *value, dumpFlags_t dumpMask, co
#ifdef DEBUG
if (!pg) {
cliPrintLinef("VALUE %s ERROR", value->name);
return; // if it's not found, the pgn shouldn't be in the value table!
return headingStr; // if it's not found, the pgn shouldn't be in the value table!
}
#endif
@ -5064,9 +5064,12 @@ static void cliDmaopt(char *cmdline)
if (!pch) {
if (entry) {
printPeripheralDmaoptDetails(entry, index, *optaddr, true, DUMP_MASTER, cliDumpPrintLinef);
} else {
}
#if defined(USE_TIMER_MGMT)
else {
printTimerDmaoptDetails(ioTag, timer, orgval, true, DUMP_MASTER, cliDumpPrintLinef);
}
#endif
return;
} else if (strcasecmp(pch, "list") == 0) {

View File

@ -69,7 +69,7 @@ typedef struct adcDevice_s {
#else
DMA_Channel_TypeDef* DMAy_Channelx;
#endif
#endif
#endif // !defined(USE_DMA_SPEC)
#if defined(STM32F7) || defined(STM32H7)
ADC_HandleTypeDef ADCHandle;
DMA_HandleTypeDef DmaHandle;

View File

@ -28,6 +28,7 @@
#include "build/debug.h"
#include "drivers/dma_reqmap.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/rcc.h"
@ -82,20 +83,26 @@ const adcDevice_t adcHardware[ADCDEV_COUNT] = {
{
.ADCx = ADC1_INSTANCE,
.rccADC = RCC_AHB1(ADC12),
#if !defined(USE_DMA_SPEC)
.DMAy_Streamx = ADC1_DMA_STREAM,
.channel = DMA_REQUEST_ADC1,
#endif
},
{ .ADCx = ADC2_INSTANCE,
.rccADC = RCC_AHB1(ADC12),
#if !defined(USE_DMA_SPEC)
.DMAy_Streamx = ADC2_DMA_STREAM,
.channel = DMA_REQUEST_ADC2,
#endif
},
// ADC3 can be serviced by BDMA also, but we settle for DMA1 or 2 (for now).
{
.ADCx = ADC3_INSTANCE,
.rccADC = RCC_AHB4(ADC3),
#if !defined(USE_DMA_SPEC)
.DMAy_Streamx = ADC3_DMA_STREAM,
.channel = DMA_REQUEST_ADC3,
#endif
}
};
@ -266,7 +273,11 @@ void adcInit(const adcConfig_t *config)
// Find an ADC device that can handle this input pin
for (dev = 0; dev < ADCDEV_COUNT; dev++) {
if (!(adcDevice[dev].ADCx && adcDevice[dev].DMAy_Streamx)) {
if (!adcDevice[dev].ADCx
#ifndef USE_DMA_SPEC
|| !adcDevice[dev].DMAy_Streamx
#endif
) {
// Instance not activated
continue;
}
@ -357,11 +368,22 @@ void adcInit(const adcConfig_t *config)
// Configure DMA for this ADC peripheral
dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(adc->DMAy_Streamx);
dmaInit(dmaIdentifier, OWNER_ADC, RESOURCE_INDEX(dev));
dmaIdentifier_e dmaIdentifier;
#ifdef USE_DMA_SPEC
const dmaChannelSpec_t *dmaSpec = dmaGetChannelSpecByPeripheral(DMA_PERIPH_ADC, dev, config->dmaopt[dev]);
if (!dmaSpec) {
return;
}
adc->DmaHandle.Instance = dmaSpec->ref;
adc->DmaHandle.Init.Request = dmaSpec->channel;
dmaIdentifier = dmaGetIdentifier(dmaSpec->ref);
#else
dmaIdentifier = dmaGetIdentifier(adc->DMAy_Streamx);
adc->DmaHandle.Instance = adc->DMAy_Streamx;
adc->DmaHandle.Init.Request = adc->channel;
#endif
adc->DmaHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
adc->DmaHandle.Init.PeriphInc = DMA_PINC_DISABLE;
adc->DmaHandle.Init.MemInc = DMA_MINC_ENABLE;
@ -375,6 +397,8 @@ void adcInit(const adcConfig_t *config)
HAL_DMA_DeInit(&adc->DmaHandle);
HAL_DMA_Init(&adc->DmaHandle);
dmaInit(dmaIdentifier, OWNER_ADC, RESOURCE_INDEX(dev));
// Associate the DMA handle
__HAL_LINKDMA(&adc->ADCHandle, DMA_Handle, adc->DmaHandle);

View File

@ -37,16 +37,149 @@
typedef struct dmaPeripheralMapping_s {
dmaPeripheral_e device;
uint8_t index;
#if defined(STM32H7)
uint8_t dmaRequest;
#else
dmaChannelSpec_t channelSpec[MAX_PERIPHERAL_DMA_OPTIONS];
#endif
} dmaPeripheralMapping_t;
typedef struct dmaTimerMapping_s {
TIM_TypeDef *tim;
uint8_t channel;
#if defined(STM32H7)
uint8_t dmaRequest;
#else
dmaChannelSpec_t channelSpec[MAX_TIMER_DMA_OPTIONS];
#endif
} dmaTimerMapping_t;
#if defined(STM32F4) || defined(STM32F7)
#if defined(STM32H7)
#define REQMAP_SGL(periph) { DMA_PERIPH_ ## periph, 0, DMA_REQUEST_ ## periph }
#define REQMAP(periph, device) { DMA_PERIPH_ ## periph, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device }
#define REQMAP_DIR(periph, device, dir) { DMA_PERIPH_ ## periph ## _ ## dir, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device ## _ ## dir }
// Resolve UART/UART mess
#define DMA_REQUEST_UART1_RX DMA_REQUEST_USART1_RX
#define DMA_REQUEST_UART1_TX DMA_REQUEST_USART1_TX
#define DMA_REQUEST_UART2_RX DMA_REQUEST_USART2_RX
#define DMA_REQUEST_UART2_TX DMA_REQUEST_USART2_TX
#define DMA_REQUEST_UART3_RX DMA_REQUEST_USART3_RX
#define DMA_REQUEST_UART3_TX DMA_REQUEST_USART3_TX
#define DMA_REQUEST_UART6_RX DMA_REQUEST_USART6_RX
#define DMA_REQUEST_UART6_TX DMA_REQUEST_USART6_TX
static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
#ifdef USE_SPI
REQMAP_DIR(SPI, 1, TX),
REQMAP_DIR(SPI, 1, RX),
REQMAP_DIR(SPI, 2, TX),
REQMAP_DIR(SPI, 2, RX),
REQMAP_DIR(SPI, 3, TX),
REQMAP_DIR(SPI, 3, RX),
REQMAP_DIR(SPI, 4, TX),
REQMAP_DIR(SPI, 4, RX),
// REQMAP_DIR(SPI, 5, TX), // Not available in smaller packages
// REQMAP_DIR(SPI, 5, TX), // ditto
// REQMAP_DIR(SPI, 6, TX), // SPI6 is on BDMA (todo)
// REQMAP_DIR(SPI, 6, TX), // ditto
#endif // USE_SPI
#ifdef USE_ADC
REQMAP(ADC, 1),
REQMAP(ADC, 2),
REQMAP(ADC, 3),
#endif
#ifdef USE_SDCARD_SDIO
REQMAP_SGL(SDIO),
#endif
#ifdef USE_UART
REQMAP_DIR(UART, 1, TX),
REQMAP_DIR(UART, 1, RX),
REQMAP_DIR(UART, 2, TX),
REQMAP_DIR(UART, 2, RX),
REQMAP_DIR(UART, 3, TX),
REQMAP_DIR(UART, 3, RX),
REQMAP_DIR(UART, 4, TX),
REQMAP_DIR(UART, 4, RX),
REQMAP_DIR(UART, 5, TX),
REQMAP_DIR(UART, 5, RX),
REQMAP_DIR(UART, 6, TX),
REQMAP_DIR(UART, 6, RX),
REQMAP_DIR(UART, 7, TX),
REQMAP_DIR(UART, 7, RX),
REQMAP_DIR(UART, 8, TX),
REQMAP_DIR(UART, 8, RX),
#endif
};
#undef REQMAP
#undef REQMAP_SGL
#undef REQMAP_DIR
#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan)
#define REQMAP_TIM(tim, chan) { tim, TC(chan), DEF_TIM_DMA_REQ__BTCH_ ## tim ## _ ## chan }
static const dmaTimerMapping_t dmaTimerMapping[] = {
REQMAP_TIM(TIM1, CH1),
REQMAP_TIM(TIM1, CH2),
REQMAP_TIM(TIM1, CH3),
REQMAP_TIM(TIM1, CH4),
REQMAP_TIM(TIM2, CH1),
REQMAP_TIM(TIM2, CH2),
REQMAP_TIM(TIM2, CH3),
REQMAP_TIM(TIM2, CH4),
REQMAP_TIM(TIM3, CH1),
REQMAP_TIM(TIM3, CH2),
REQMAP_TIM(TIM3, CH3),
REQMAP_TIM(TIM3, CH4),
REQMAP_TIM(TIM4, CH1),
REQMAP_TIM(TIM4, CH2),
REQMAP_TIM(TIM4, CH3),
REQMAP_TIM(TIM5, CH1),
REQMAP_TIM(TIM5, CH2),
REQMAP_TIM(TIM5, CH3),
REQMAP_TIM(TIM5, CH4),
REQMAP_TIM(TIM8, CH1),
REQMAP_TIM(TIM8, CH2),
REQMAP_TIM(TIM8, CH3),
REQMAP_TIM(TIM8, CH4),
REQMAP_TIM(TIM15, CH1),
REQMAP_TIM(TIM16, CH1),
REQMAP_TIM(TIM17, CH1),
};
#undef TC
#undef REQMAP_TIM
#define DMA(d, s) { DMA_CODE(d, s, 0), DMA ## d ## _Stream ## s, 0 }
static dmaChannelSpec_t dmaChannelSpec[MAX_PERIPHERAL_DMA_OPTIONS] = {
DMA(1, 0),
DMA(1, 1),
DMA(1, 2),
DMA(1, 3),
DMA(1, 4),
DMA(1, 5),
DMA(1, 6),
DMA(1, 7),
DMA(2, 0),
DMA(2, 1),
DMA(2, 2),
DMA(2, 3),
DMA(2, 4),
DMA(2, 5),
DMA(2, 6),
DMA(2, 7),
};
#undef DMA
#elif defined(STM32F4) || defined(STM32F7)
#if defined(STM32F4)
#define DMA(d, s, c) { DMA_CODE(d, s, c), DMA ## d ## _Stream ## s, DMA_Channel_ ## c }
@ -225,6 +358,18 @@ static const dmaTimerMapping_t dmaTimerMapping[] = {
#undef DMA
#endif
#if defined(STM32H7)
static void dmaSetupRequest(dmaChannelSpec_t *dmaSpec, uint8_t request)
{
// Setup request as channel
dmaSpec->channel = request;
// Insert DMA request into code
dmaCode_t code = dmaSpec->code;
dmaSpec->code = DMA_CODE(DMA_CODE_CONTROLLER(code), DMA_CODE_STREAM(code), dmaSpec->channel);
}
#endif
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
{
if (opt < 0 || opt >= MAX_PERIPHERAL_DMA_OPTIONS) {
@ -233,9 +378,17 @@ const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, ui
for (unsigned i = 0 ; i < ARRAYLEN(dmaPeripheralMapping) ; i++) {
const dmaPeripheralMapping_t *periph = &dmaPeripheralMapping[i];
#if defined(STM32H7)
if (periph->device == device && periph->index == index) {
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[opt];
dmaSetupRequest(dmaSpec, periph->dmaRequest);
return dmaSpec;
}
#else
if (periph->device == device && periph->index == index && periph->channelSpec[opt].ref) {
return &periph->channelSpec[opt];
}
#endif
}
return NULL;
@ -250,6 +403,18 @@ dmaoptValue_t dmaoptByTag(ioTag_t ioTag)
}
}
#else
#if defined(STM32H7)
const timerHardware_t *timhw = timerGetByTag(ioTag);
if (timhw && timhw->dmaRefConfigured && timhw->dmaChannelConfigured) {
// Reverse lookup dmaopt from dmaRefConfigured by utilizing dmaChannelSpec array
unsigned opt;
for (opt = 0; opt < ARRAYLEN(dmaChannelSpec); opt++) {
if (timhw->dmaRefConfigured == dmaChannelSpec[opt].ref) {
return (dmaoptValue_t)opt;
}
}
}
#endif
UNUSED(ioTag);
#endif
@ -264,9 +429,17 @@ const dmaChannelSpec_t *dmaGetChannelSpecByTimerValue(TIM_TypeDef *tim, uint8_t
for (unsigned i = 0 ; i < ARRAYLEN(dmaTimerMapping) ; i++) {
const dmaTimerMapping_t *timerMapping = &dmaTimerMapping[i];
#if defined(STM32H7)
if (timerMapping->tim == tim && timerMapping->channel == channel) {
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[dmaopt];
dmaSetupRequest(dmaSpec, timerMapping->dmaRequest);
return dmaSpec;
}
#else
if (timerMapping->tim == tim && timerMapping->channel == channel && timerMapping->channelSpec[dmaopt].ref) {
return &timerMapping->channelSpec[dmaopt];
}
#endif
}
return NULL;
@ -287,6 +460,9 @@ dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
for (unsigned i = 0 ; i < ARRAYLEN(dmaTimerMapping); i++) {
const dmaTimerMapping_t *timerMapping = &dmaTimerMapping[i];
if (timerMapping->tim == timer->tim && timerMapping->channel == timer->channel) {
#if defined(STM32H7)
return timerMapping->dmaRequest;
#else
for (unsigned j = 0; j < MAX_TIMER_DMA_OPTIONS; j++) {
const dmaChannelSpec_t *dma = &timerMapping->channelSpec[j];
if (dma->ref == timer->dmaRefConfigured
@ -297,7 +473,7 @@ dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
return j;
}
}
#endif
}
}

View File

@ -55,8 +55,13 @@ typedef int8_t dmaoptValue_t;
#define DMA_OPT_UNUSED (-1)
#if defined(STM32H7)
#define MAX_PERIPHERAL_DMA_OPTIONS 16
#define MAX_TIMER_DMA_OPTIONS 16
#else
#define MAX_PERIPHERAL_DMA_OPTIONS 2
#define MAX_TIMER_DMA_OPTIONS 3
#endif
dmaoptValue_t dmaoptByTag(ioTag_t ioTag);
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt);

View File

@ -27,6 +27,7 @@
#ifdef USE_DSHOT
#include "drivers/dma_reqmap.h"
#include "drivers/io.h"
#include "timer.h"
#include "pwm_output.h"
@ -152,7 +153,13 @@ void pwmWriteDshotInt(uint8_t index, uint16_t value)
}
}
if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
if (!motor->timerHardware
#ifndef USE_DMA_SPEC
// When USE_DMA_SPEC is in effect, motor->timerHardware remains NULL if valid DMA is not assigned.
|| !motor->timerHardware->dmaRef
#endif
)
{
return;
}
@ -228,16 +235,27 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
{
DMA_Stream_TypeDef *dmaRef;
DMA_Stream_TypeDef *dmaRef = NULL;
uint32_t dmaChannel;
#ifdef USE_DMA_SPEC
const dmaChannelSpec_t *dmaSpec = dmaGetChannelSpecByTimer(timerHardware);
if (dmaSpec) {
dmaRef = dmaSpec->ref;
dmaChannel = dmaSpec->channel;
}
#else
dmaRef = timerHardware->dmaRef;
dmaChannel = timerHardware->dmaChannel;
#endif
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
dmaRef = timerHardware->dmaTimUPRef;
} else
#endif
{
dmaRef = timerHardware->dmaRef;
dmaChannel = timerHardware->dmaTimUPChannel;
}
#endif
if (dmaRef == NULL) {
return;
@ -352,7 +370,7 @@ P - High - High -
/* Set hdma_tim instance */
motor->timer->hdma_tim.Instance = timerHardware->dmaTimUPRef;
motor->timer->hdma_tim.Init.Request = timerHardware->dmaTimUPRequest;
motor->timer->hdma_tim.Init.Request = timerHardware->dmaTimUPChannel;
/* Link hdma_tim to hdma[TIM_DMA_ID_UPDATE] (update) */
__HAL_LINKDMA(&motor->timer->timHandle, hdma[TIM_DMA_ID_UPDATE], motor->timer->hdma_tim);
@ -379,8 +397,8 @@ P - High - High -
motor->dmaBuffer[DSHOT_DMA_BUFFER_SIZE-2] = 0; // XXX Is this necessary? -> probably.
motor->dmaBuffer[DSHOT_DMA_BUFFER_SIZE-1] = 0; // XXX Is this necessary?
motor->hdma_tim.Instance = timerHardware->dmaRef;
motor->hdma_tim.Init.Request = timerHardware->dmaChannel;
motor->hdma_tim.Instance = dmaRef;
motor->hdma_tim.Init.Request = dmaChannel;
/* Link hdma_tim to hdma[x] (channelx) */
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
@ -402,7 +420,7 @@ P - High - High -
} else
#endif
{
dmaIdentifier_e identifier = dmaGetIdentifier(timerHardware->dmaRef);
dmaIdentifier_e identifier = dmaGetIdentifier(dmaRef);
dmaInit(identifier, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
dmaSetHandler(identifier, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
}

View File

@ -123,10 +123,8 @@ typedef struct timerHardware_s {
#else
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
DMA_Stream_TypeDef *dmaRef;
// For F4 and F7, dmaChannel is channel for DMA1 or DMA2.
// For H7, dmaChannel is DMA request number for DMAMUX
uint32_t dmaChannel; // XXX Can be much smaller (e.g. uint8_t)
#else
DMA_Channel_TypeDef *dmaRef;
@ -137,11 +135,10 @@ typedef struct timerHardware_s {
// TIMUP
#ifdef STM32F3
DMA_Channel_TypeDef *dmaTimUPRef;
#elif defined(STM32H7)
DMA_Stream_TypeDef *dmaTimUPRef;
uint8_t dmaTimUPRequest;
#else
DMA_Stream_TypeDef *dmaTimUPRef;
// For F4 and F7, dmaTimUpChannel is channel for DMA1 or DMA2.
// For H7, dmaTimUpChannel is DMA request number for DMAMUX
uint32_t dmaTimUPChannel;
#endif
uint8_t dmaTimUPIrqHandler;

View File

@ -104,6 +104,7 @@
#define USE_GYRO_DATA_ANALYSE
#define USE_ADC_INTERNAL
#define USE_USB_CDC_HID
#define USE_DMA_SPEC
#endif
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)