diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 2ca7d60790..17b18e106e 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -42,6 +42,13 @@ static FAST_RAM_ZERO_INIT pwmStartWriteFn *pwmStartWrite = NULL; #endif #ifdef USE_DSHOT +#ifdef STM32H7 +// XXX dshotDmaBuffer can be embedded inside dshotBurstDmaBuffer +DMA_RAM uint32_t dshotDmaBuffer[MAX_SUPPORTED_MOTORS][DSHOT_DMA_BUFFER_SIZE]; +#ifdef USE_DSHOT_DMAR +DMA_RAM uint32_t dshotBurstDmaBuffer[MAX_DMA_TIMERS][DSHOT_DMA_BUFFER_SIZE * 4]; +#endif +#endif FAST_RAM_ZERO_INIT loadDmaBufferFn *loadDmaBuffer; #define DSHOT_INITIAL_DELAY_US 10000 #define DSHOT_COMMAND_DELAY_US 1000 diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index b36771a033..43ddc19df7 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -125,13 +125,21 @@ typedef enum { typedef struct { TIM_TypeDef *timer; #if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR) +#if defined(STM32F7) || defined(STM32H7) + TIM_HandleTypeDef timHandle; + DMA_HandleTypeDef hdma_tim; +#endif #ifdef STM32F3 DMA_Channel_TypeDef *dmaBurstRef; #else DMA_Stream_TypeDef *dmaBurstRef; #endif uint16_t dmaBurstLength; +#ifdef STM32H7 + uint32_t *dmaBurstBuffer; +#else uint32_t dmaBurstBuffer[DSHOT_DMA_BUFFER_SIZE * 4]; +#endif timeUs_t inputDirectionStampUs; #endif uint16_t timerDmaSources; @@ -143,7 +151,12 @@ typedef struct { uint16_t value; #ifdef USE_DSHOT uint16_t timerDmaSource; + uint8_t timerDmaIndex; bool configured; +#ifdef STM32H7 + TIM_HandleTypeDef TimHandle; + DMA_HandleTypeDef hdma_tim; +#endif uint8_t output; uint8_t index; #ifdef USE_DSHOT_TELEMETRY @@ -178,6 +191,8 @@ typedef struct { #else #if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) uint32_t dmaBuffer[DSHOT_DMA_BUFFER_SIZE]; +#elif defined(STM32H7) + uint32_t *dmaBuffer; #else uint8_t dmaBuffer[DSHOT_DMA_BUFFER_SIZE]; #endif @@ -242,6 +257,13 @@ typedef uint8_t loadDmaBufferFn(uint32_t *dmaBuffer, int stride, uint16_t packet uint16_t prepareDshotPacket(motorDmaOutput_t *const motor); +#ifdef STM32H7 +extern DMA_RAM uint32_t dshotDmaBuffer[MAX_SUPPORTED_MOTORS][DSHOT_DMA_BUFFER_SIZE]; +#ifdef USE_DSHOT_DMAR +extern DMA_RAM uint32_t dshotBurstDmaBuffer[MAX_DMA_TIMERS][DSHOT_DMA_BUFFER_SIZE * 4]; +#endif +#endif + extern loadDmaBufferFn *loadDmaBuffer; uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType); diff --git a/src/main/drivers/pwm_output_dshot_hal_hal.c b/src/main/drivers/pwm_output_dshot_hal_hal.c new file mode 100644 index 0000000000..c6199e7d26 --- /dev/null +++ b/src/main/drivers/pwm_output_dshot_hal_hal.c @@ -0,0 +1,425 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include +#include + +#include "platform.h" + +#ifdef USE_DSHOT + +#include "drivers/io.h" +#include "timer.h" +#include "pwm_output.h" +#include "drivers/nvic.h" +#include "dma.h" +#include "rcc.h" + +static HAL_StatusTypeDef result; + +static uint8_t dmaMotorTimerCount = 0; +static motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS]; +static motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS]; + +motorDmaOutput_t *getMotorDmaOutput(uint8_t index) +{ + return &dmaMotors[index]; +} + +uint8_t getTimerIndex(TIM_TypeDef *timer) +{ + for (int i = 0; i < dmaMotorTimerCount; i++) { + if (dmaMotorTimers[i].timer == timer) { + return i; + } + } + dmaMotorTimers[dmaMotorTimerCount++].timer = timer; + return dmaMotorTimerCount - 1; +} + +// TIM_CHANNEL_x TIM_CHANNEL_x/4 TIM_DMA_ID_CCx TIM_DMA_CCx +// 0x0 0 1 0x0200 +// 0x4 1 2 0x0400 +// 0x8 2 3 0x0800 +// 0xC 3 4 0x1000 +// +// TIM_CHANNEL_TO_TIM_DMA_ID_CC = (TIM_CHANNEL_x / 4) + 1 +// TIM_CHANNEL_TO_TIM_DMA_CC = 0x200 << (TIM_CHANNEL_x / 4) + +// pwmChannelDMAStart +// A variant of HAL_TIM_PWM_Start_DMA/HAL_TIMEx_PWMN_Start_DMA that only disables DMA on a timer channel: +// 1. Configure and enable DMA Stream +// 2. Enable DMA request on a timer channel + +void pwmChannelDMAStart(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length) +{ + switch (Channel) { + case TIM_CHANNEL_1: + HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC1], (uint32_t)pData, (uint32_t)&htim->Instance->CCR1, Length); + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC1); + break; + + case TIM_CHANNEL_2: + HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC2], (uint32_t)pData, (uint32_t)&htim->Instance->CCR2, Length); + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC2); + break; + + case TIM_CHANNEL_3: + HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC3], (uint32_t)pData, (uint32_t)&htim->Instance->CCR3,Length); + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC3); + break; + + case TIM_CHANNEL_4: + HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_CC4], (uint32_t)pData, (uint32_t)&htim->Instance->CCR4, Length); + __HAL_TIM_ENABLE_DMA(htim, TIM_DMA_CC4); + break; + } +} + +// pwmChannelDMAStop +// A variant of HAL_TIM_PWM_Stop_DMA/HAL_TIMEx_PWMN_Stop_DMA that only disables DMA on a timer channel +// 1. Disable the TIM Capture/Compare 1 DMA request + +void pwmChannelDMAStop(TIM_HandleTypeDef *htim, uint32_t Channel) +{ + switch (Channel) { + case TIM_CHANNEL_1: + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1); + break; + + case TIM_CHANNEL_2: + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2); + break; + + case TIM_CHANNEL_3: + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3); + break; + + case TIM_CHANNEL_4: + __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4); + break; + } +} + +// pwmBurstDMAStart +// A variant of HAL_TIM_DMABurst_WriteStart that can handle multiple bursts. +// (HAL_TIM_DMABurst_WriteStart can only handle single burst) + +void pwmBurstDMAStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, uint32_t BurstRequestSrc, uint32_t BurstUnit, uint32_t* BurstBuffer, uint32_t BurstLength) +{ + // Setup DMA stream + HAL_DMA_Start_IT(htim->hdma[TIM_DMA_ID_UPDATE], (uint32_t)BurstBuffer, (uint32_t)&htim->Instance->DMAR, BurstLength); + + // Configure burst mode DMA */ + htim->Instance->DCR = BurstBaseAddress | BurstUnit; + + // Enable burst mode DMA + __HAL_TIM_ENABLE_DMA(htim, BurstRequestSrc); +} + +void pwmWriteDshotInt(uint8_t index, uint16_t value) +{ + motorDmaOutput_t *const motor = &dmaMotors[index]; + + if (!motor->configured) { + return; + } + + /*If there is a command ready to go overwrite the value and send that instead*/ + if (pwmDshotCommandIsProcessing()) { + value = pwmGetDshotCommand(index); + if (value) { + motor->requestTelemetry = true; + } + } + + if (!motor->timerHardware || !motor->timerHardware->dmaRef) { + return; + } + + motor->value = value; + + uint16_t packet = prepareDshotPacket(motor); + uint8_t bufferSize; + +#ifdef USE_DSHOT_DMAR + if (useBurstDshot) { + bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet); + motor->timer->dmaBurstLength = bufferSize * 4; + } else +#endif + { + bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet); + + pwmChannelDMAStart(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize); + } +} + +void pwmCompleteDshotMotorUpdate(uint8_t motorCount) +{ + UNUSED(motorCount); + + // If there is a dshot command loaded up, time it correctly with motor update + + if (pwmDshotCommandIsQueued()) { + if (!pwmDshotCommandOutputIsEnabled(motorCount)) { + return; + } + } + +#ifdef USE_DSHOT_DMAR + if (useBurstDshot) { + for (int i = 0; i < dmaMotorTimerCount; i++) { + motorDmaTimer_t *burstDmaTimer = &dmaMotorTimers[i]; + + // Transfer CCR1 through CCR4 for each burst + pwmBurstDMAStart(&burstDmaTimer->timHandle, + TIM_DMABASE_CCR1, TIM_DMA_UPDATE, TIM_DMABURSTLENGTH_4TRANSFERS, + (uint32_t*)burstDmaTimer->dmaBurstBuffer, burstDmaTimer->dmaBurstLength); + } + } else +#endif + { + // XXX Empty for non-burst? + } +} + +static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) +{ + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + +#ifdef USE_DSHOT_DMAR + if (useBurstDshot) { + motorDmaTimer_t *burstDmaTimer = &dmaMotorTimers[descriptor->userParam]; + + HAL_TIM_DMABurst_WriteStop(&burstDmaTimer->timHandle, TIM_DMA_UPDATE); + HAL_DMA_IRQHandler(&burstDmaTimer->hdma_tim); + } else +#endif + { + motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam]; + + pwmChannelDMAStop(&motor->TimHandle,motor->timerHardware->channel); + HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaIndex]); + } + + DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); + } +} + +void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output) +{ + DMA_Stream_TypeDef *dmaRef; + +#ifdef USE_DSHOT_DMAR + if (useBurstDshot) { + dmaRef = timerHardware->dmaTimUPRef; + } else +#endif + { + dmaRef = timerHardware->dmaRef; + } + + if (dmaRef == NULL) { + return; + } + + motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; + motor->timerHardware = timerHardware; + + TIM_TypeDef *timer = timerHardware->tim; // "timer" is confusing; "tim"? + const IO_t motorIO = IOGetByTag(timerHardware->tag); + + const uint8_t timerIndex = getTimerIndex(timer); + const bool configureTimer = (timerIndex == dmaMotorTimerCount - 1); + + IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); + IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN), timerHardware->alternateFunction); + + // Configure time base + + if (configureTimer) { + RCC_ClockCmd(timerRCC(timer), ENABLE); + + motor->TimHandle.Instance = timerHardware->tim; // timer + motor->TimHandle.Init.Prescaler = (uint16_t)(lrintf((float) timerClock(timer) / getDshotHz(pwmProtocolType) + 0.01f) - 1); + motor->TimHandle.Init.Period = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH; + motor->TimHandle.Init.RepetitionCounter = 0; + motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; + motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; + motor->TimHandle.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; + + result = HAL_TIM_PWM_Init(&motor->TimHandle); + + if (result != HAL_OK) { + /* Initialization Error */ + return; + } + } + +/* +From LL version +chan oinv IDLE NIDLE POL NPOL +N I - Low - Low +N - - Low - High +P I High - Low - +P - High - High - +*/ + + /* PWM mode 1 configuration */ + + TIM_OC_InitTypeDef TIM_OCInitStructure; + TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1; + + if (output & TIMER_OUTPUT_N_CHANNEL) { + TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET; + TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_HIGH : TIM_OCPOLARITY_LOW; + TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET; + TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_HIGH : TIM_OCNPOLARITY_LOW; + } else { + TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_SET; + TIM_OCInitStructure.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPOLARITY_LOW : TIM_OCPOLARITY_HIGH; + TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_SET; + TIM_OCInitStructure.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPOLARITY_LOW : TIM_OCNPOLARITY_HIGH; + } + TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE; + TIM_OCInitStructure.Pulse = 0; + + result = HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel); + + if (result != HAL_OK) { + /* Configuration Error */ + return; + } + + // DMA setup + + motor->timer = &dmaMotorTimers[timerIndex]; + +#ifdef USE_DSHOT_DMAR + if (useBurstDshot) { + motor->timer->dmaBurstRef = dmaRef; + + if (!configureTimer) { + motor->configured = true; + return; + } + } else +#endif + { + motor->timerDmaSource = timerDmaSource(timerHardware->channel); + motor->timer->timerDmaSources |= motor->timerDmaSource; + motor->timerDmaIndex = timerDmaIndex(timerHardware->channel); + } + + +#ifdef USE_DSHOT_DMAR + if (useBurstDshot) { + motor->timer->hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH; + motor->timer->hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE; + motor->timer->hdma_tim.Init.MemInc = DMA_MINC_ENABLE; + motor->timer->hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD ; + motor->timer->hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD ; + motor->timer->hdma_tim.Init.Mode = DMA_NORMAL; + motor->timer->hdma_tim.Init.Priority = DMA_PRIORITY_HIGH; + motor->timer->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + motor->timer->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; + motor->timer->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; + motor->timer->hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + + motor->timer->dmaBurstBuffer = &dshotBurstDmaBuffer[timerIndex][0]; + motor->timer->timHandle = motor->TimHandle; + memset(motor->timer->dmaBurstBuffer, 0, DSHOT_DMA_BUFFER_SIZE * 4 * sizeof(uint32_t)); + + /* Set hdma_tim instance */ + motor->timer->hdma_tim.Instance = timerHardware->dmaTimUPRef; + motor->timer->hdma_tim.Init.Request = timerHardware->dmaTimUPRequest; + + /* Link hdma_tim to hdma[TIM_DMA_ID_UPDATE] (update) */ + __HAL_LINKDMA(&motor->timer->timHandle, hdma[TIM_DMA_ID_UPDATE], motor->timer->hdma_tim); + + /* Initialize TIMx DMA handle */ + result = HAL_DMA_Init(motor->timer->timHandle.hdma[TIM_DMA_ID_UPDATE]); + + } else +#endif + { + motor->hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH; + motor->hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE; + motor->hdma_tim.Init.MemInc = DMA_MINC_ENABLE; + motor->hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD ; + motor->hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD ; + motor->hdma_tim.Init.Mode = DMA_NORMAL; + motor->hdma_tim.Init.Priority = DMA_PRIORITY_HIGH; + motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; + motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; + motor->hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; + + motor->dmaBuffer = &dshotDmaBuffer[motorIndex][0]; + 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->dmaRequest; + + /* Link hdma_tim to hdma[x] (channelx) */ + __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim); + + /* Initialize TIMx DMA handle */ + result = HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaIndex]); + + } + + if (result != HAL_OK) { + /* Initialization Error */ + return; + } + +#ifdef USE_DSHOT_DMAR + if (useBurstDshot) { + dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim)); + dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), timerIndex); + } else +#endif + { + dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); + dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex); + } + + // Start the timer channel now. + // Enabling/disabling DMA request can restart a new cycle without PWM start/stop. + + if (motor->timerHardware->output & TIMER_OUTPUT_N_CHANNEL) { + result = HAL_TIMEx_PWMN_Start(&motor->TimHandle, motor->timerHardware->channel); + } else { + result = HAL_TIM_PWM_Start(&motor->TimHandle, motor->timerHardware->channel); + } + + if (result != HAL_OK) { + /* Starting PWM generation Error */ + return; + } + + motor->configured = true; +} +#endif