1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +03:00

Revert DSHOT Interrupt

This commit is contained in:
borisbstyle 2017-02-23 01:19:17 +01:00
parent 792941606f
commit d3ac73a0a0
5 changed files with 39 additions and 23 deletions

View file

@ -105,13 +105,3 @@ dmaIdentifier_e dmaGetIdentifier(const DMA_Channel_TypeDef* channel)
} }
return 0; 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;
}

View file

@ -129,7 +129,7 @@ typedef enum {
#define DMA_IT_TEIF ((uint32_t)0x00000008) #define DMA_IT_TEIF ((uint32_t)0x00000008)
dmaIdentifier_e dmaGetIdentifier(const DMA_Channel_TypeDef* channel); dmaIdentifier_e dmaGetIdentifier(const DMA_Channel_TypeDef* channel);
dmaChannelDescriptor_t* getDmaDescriptor(const DMA_Channel_TypeDef* channel);
#endif #endif
void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex); void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex);

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#include "dma.h"
#include "io_types.h" #include "io_types.h"
#include "timer.h" #include "timer.h"
@ -94,7 +93,6 @@ typedef struct {
#else #else
uint8_t dmaBuffer[MOTOR_DMA_BUFFER_SIZE]; uint8_t dmaBuffer[MOTOR_DMA_BUFFER_SIZE];
#endif #endif
dmaChannelDescriptor_t* dmaDescriptor;
#if defined(STM32F7) #if defined(STM32F7)
TIM_HandleTypeDef TimHandle; TIM_HandleTypeDef TimHandle;
DMA_HandleTypeDef hdma_tim; DMA_HandleTypeDef hdma_tim;

View file

@ -85,10 +85,7 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
packet <<= 1; 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_SetCurrDataCounter(motor->timerHardware->dmaRef, MOTOR_DMA_BUFFER_SIZE);
DMA_CLEAR_FLAG(motor->dmaDescriptor, DMA_IT_TCIF);
DMA_Cmd(motor->timerHardware->dmaRef, ENABLE); 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) void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
{ {
TIM_OCInitTypeDef TIM_OCInitStructure; TIM_OCInitTypeDef TIM_OCInitStructure;
@ -177,10 +184,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
} }
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
motor->dmaDescriptor = getDmaDescriptor(dmaRef); dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
DMA_Cmd(dmaRef, DISABLE);
DMA_DeInit(dmaRef);
DMA_StructInit(&DMA_InitStructure); DMA_StructInit(&DMA_InitStructure);
#if defined(STM32F3) #if defined(STM32F3)
@ -206,6 +210,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_Init(dmaRef, &DMA_InitStructure); DMA_Init(dmaRef, &DMA_InitStructure);
DMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
} }
#endif #endif

View file

@ -81,9 +81,6 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
packet <<= 1; 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) if(HAL_TIM_PWM_Start_DMA(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, MOTOR_DMA_BUFFER_SIZE) != HAL_OK)
{ {
/* Starting PWM generation Error */ /* Starting PWM generation Error */
@ -94,8 +91,33 @@ void pwmWriteDigital(uint8_t index, uint16_t value)
void pwmCompleteDigitalMotorUpdate(uint8_t motorCount) void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
{ {
UNUSED(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) void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
{ {
motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; 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); __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim);
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
/* Initialize TIMx DMA handle */ /* Initialize TIMx DMA handle */
if(HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK) if(HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaSource]) != HAL_OK)