diff --git a/src/main/drivers/dma.c b/src/main/drivers/dma.c index 6a544915ea..a8d6cf9cb5 100644 --- a/src/main/drivers/dma.c +++ b/src/main/drivers/dma.c @@ -105,13 +105,3 @@ dmaIdentifier_e dmaGetIdentifier(const DMA_Channel_TypeDef* channel) } return 0; } - -dmaChannelDescriptor_t* getDmaDescriptor(const DMA_Channel_TypeDef* channel) -{ - for (int i = 0; i < DMA_MAX_DESCRIPTORS; i++) { - if (dmaDescriptors[i].ref == channel) { - return &dmaDescriptors[i]; - } - } - return NULL; -} \ No newline at end of file diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 29910bc025..c5831c95e1 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -129,7 +129,7 @@ typedef enum { #define DMA_IT_TEIF ((uint32_t)0x00000008) dmaIdentifier_e dmaGetIdentifier(const DMA_Channel_TypeDef* channel); -dmaChannelDescriptor_t* getDmaDescriptor(const DMA_Channel_TypeDef* channel); + #endif void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex); diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index f43ba861e1..b71d1ddfe8 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -17,7 +17,6 @@ #pragma once -#include "dma.h" #include "io_types.h" #include "timer.h" @@ -94,7 +93,6 @@ typedef struct { #else uint8_t dmaBuffer[MOTOR_DMA_BUFFER_SIZE]; #endif - dmaChannelDescriptor_t* dmaDescriptor; #if defined(STM32F7) TIM_HandleTypeDef TimHandle; DMA_HandleTypeDef hdma_tim; diff --git a/src/main/drivers/pwm_output_dshot.c b/src/main/drivers/pwm_output_dshot.c index 66ac9fd5c8..47e6b6824b 100644 --- a/src/main/drivers/pwm_output_dshot.c +++ b/src/main/drivers/pwm_output_dshot.c @@ -85,10 +85,7 @@ void pwmWriteDigital(uint8_t index, uint16_t value) packet <<= 1; } - DMA_Cmd(motor->timerHardware->dmaRef, DISABLE); - TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE); DMA_SetCurrDataCounter(motor->timerHardware->dmaRef, MOTOR_DMA_BUFFER_SIZE); - DMA_CLEAR_FLAG(motor->dmaDescriptor, DMA_IT_TCIF); DMA_Cmd(motor->timerHardware->dmaRef, ENABLE); } @@ -106,6 +103,16 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount) } } +static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) +{ + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam]; + DMA_Cmd(motor->timerHardware->dmaRef, DISABLE); + TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + } +} + void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output) { TIM_OCInitTypeDef TIM_OCInitStructure; @@ -177,10 +184,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t } dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); - motor->dmaDescriptor = getDmaDescriptor(dmaRef); - - DMA_Cmd(dmaRef, DISABLE); - DMA_DeInit(dmaRef); + dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex); DMA_StructInit(&DMA_InitStructure); #if defined(STM32F3) @@ -206,6 +210,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_Init(dmaRef, &DMA_InitStructure); + DMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE); } #endif diff --git a/src/main/drivers/pwm_output_stm32f7xx.c b/src/main/drivers/pwm_output_stm32f7xx.c index 66df5c1228..dc34afbf95 100644 --- a/src/main/drivers/pwm_output_stm32f7xx.c +++ b/src/main/drivers/pwm_output_stm32f7xx.c @@ -81,9 +81,6 @@ void pwmWriteDigital(uint8_t index, uint16_t value) packet <<= 1; } - /* may not be required */ - HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaSource]); - if(HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK) { /* Starting PWM generation Error */ @@ -94,8 +91,33 @@ void pwmWriteDigital(uint8_t index, uint16_t value) void pwmCompleteDigitalMotorUpdate(uint8_t motorCount) { UNUSED(motorCount); + + if (!pwmMotorsEnabled) { + return; + } + + for (uint8_t i = 0; i < dmaMotorTimerCount; i++) { + //TIM_SetCounter(dmaMotorTimers[i].timer, 0); + //TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE); + } } +static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) +{ + motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam]; + HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaSource]); +} + +/*static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) +{ + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam]; + DMA_Cmd(descriptor->stream, DISABLE); + TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE); + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + } +}*/ + void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output) { motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; @@ -162,6 +184,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim); dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); + dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex); /* Initialize TIMx DMA handle */ if(HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK)