From fa3c7e0833ccc5ed535ba15491f4e34b19671173 Mon Sep 17 00:00:00 2001 From: Andrey Mironov Date: Tue, 20 Feb 2018 00:49:10 +0300 Subject: [PATCH 1/6] Rewritten F7 dshot to LL (draft) --- src/main/drivers/pwm_output.h | 7 - src/main/drivers/pwm_output_dshot_hal.c | 311 ++++++++++++------------ src/main/target/stm32f7xx_hal_conf.h | 2 +- src/main/target/system_stm32f7xx.c | 2 +- 4 files changed, 163 insertions(+), 159 deletions(-) diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 52de887fe..3e4dd3e03 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -110,12 +110,10 @@ typedef enum { typedef struct { TIM_TypeDef *timer; #if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR) -#if !defined(USE_HAL_DRIVER) #ifdef STM32F3 DMA_Channel_TypeDef *dmaBurstRef; #else DMA_Stream_TypeDef *dmaBurstRef; -#endif uint16_t dmaBurstLength; #endif #endif @@ -138,11 +136,6 @@ typedef struct { #else uint8_t dmaBuffer[DSHOT_DMA_BUFFER_SIZE]; #endif -#if defined(USE_HAL_DRIVER) - TIM_HandleTypeDef TimHandle; - DMA_HandleTypeDef hdma_tim; - uint16_t timerDmaIndex; -#endif } motorDmaOutput_t; motorDmaOutput_t *getMotorDmaOutput(uint8_t index); diff --git a/src/main/drivers/pwm_output_dshot_hal.c b/src/main/drivers/pwm_output_dshot_hal.c index 9e4bd4551..9b7e65baa 100644 --- a/src/main/drivers/pwm_output_dshot_hal.c +++ b/src/main/drivers/pwm_output_dshot_hal.c @@ -58,232 +58,243 @@ void pwmWriteDshotInt(uint8_t index, uint16_t value) } uint16_t packet = prepareDshotPacket(motor, value); - uint8_t bufferSize; #ifdef USE_DSHOT_DMAR if (useBurstDshot) { bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet); - if (HAL_DMA_STATE_READY == motor->TimHandle.hdma[motor->timerDmaIndex]->State) { - HAL_DMA_Start_IT(motor->TimHandle.hdma[motor->timerDmaIndex], (uint32_t)motor->timer->dmaBurstBuffer, (uint32_t)&motor->TimHandle.Instance->DMAR, bufferSize * 4); - } + motor->timer->dmaBurstLength = bufferSize * 4; } else #endif { bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet); - - if (DMA_SetCurrDataCounter(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) { - /* DMA set error */ - return; - } + motor->timer->timerDmaSources |= motor->timerDmaSource; + // @todo LL_DMA_SetDataLength + MODIFY_REG(motor->timerHardware->dmaRef->NDTR, DMA_SxNDT, bufferSize); + // @todo LL_DMA_EnableStream + SET_BIT(motor->timerHardware->dmaRef->CR, DMA_SxCR_EN); } } void pwmCompleteDshotMotorUpdate(uint8_t motorCount) { UNUSED(motorCount); + for (int i = 0; i < dmaMotorTimerCount; i++) { #ifdef USE_DSHOT_DMAR if (useBurstDshot) { + // @todo LL_DMA_SetDataLength + MODIFY_REG(dmaMotorTimers[i].dmaBurstRef->NDTR, DMA_SxNDT, dmaMotorTimers[i].dmaBurstLength); + // @todo LL_DMA_EnableStream + SET_BIT(dmaMotorTimers[i].dmaBurstRef->CR, DMA_SxCR_EN); + /* configure the DMA Burst Mode */ LL_TIM_ConfigDMABurst(dmaMotorTimers[i].timer, LL_TIM_DMABURST_BASEADDR_CCR1, LL_TIM_DMABURST_LENGTH_4TRANSFERS); /* Enable the TIM DMA Request */ LL_TIM_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer); - /* Reset timer counter */ - LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0); - if(IS_TIM_ADVANCED_INSTANCE(dmaMotorTimers[i].timer) != RESET) { - /* Enable the main output */ - LL_TIM_EnableAllOutputs(dmaMotorTimers[i].timer); - } - /* Enable the counter */ - LL_TIM_EnableCounter(dmaMotorTimers[i].timer); } else #endif { /* Reset timer counter */ LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0); /* Enable channel DMA requests */ - dmaMotorTimers[i].timer->DIER |= dmaMotorTimers[i].timerDmaSources; + SET_BIT(dmaMotorTimers[i].timer->DIER, dmaMotorTimers[i].timerDmaSources); + dmaMotorTimers[i].timerDmaSources = 0; } } } static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) { - motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam]; - HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaIndex]); + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) { + motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam]; + #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - LL_TIM_DisableCounter(motor->timerHardware->tim); - LL_TIM_DisableDMAReq_UPDATE(motor->timerHardware->tim); - } else + if (useBurstDshot) { + // @todo LL_DMA_DisableStream + CLEAR_BIT(motor->timerHardware->dmaTimUPRef->CR, DMA_SxCR_EN); + LL_TIM_DisableDMAReq_UPDATE(motor->timerHardware->tim); + } else #endif - { - __HAL_DMA_DISABLE(&motor->hdma_tim); - TIM_DMACmd(&motor->TimHandle, motor->timerHardware->channel, DISABLE); + { + // @todo LL_DMA_DisableStream + CLEAR_BIT(motor->timerHardware->dmaRef->CR, DMA_SxCR_EN); + CLEAR_BIT(motor->timerHardware->tim->DIER, motor->timerDmaSource); + } + + 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 && timerHardware->dmaTimUPRef == NULL) { - return; + if (useBurstDshot) { + dmaRef = timerHardware->dmaTimUPRef; } else #endif - if (timerHardware->dmaRef == NULL) { + { + dmaRef = timerHardware->dmaRef; + } + + if (dmaRef == NULL) { return; } + LL_TIM_OC_InitTypeDef oc_init; + LL_DMA_InitTypeDef dma_init; + motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; motor->timerHardware = timerHardware; TIM_TypeDef *timer = timerHardware->tim; const IO_t motorIO = IOGetByTag(timerHardware->tag); - IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLDOWN), timerHardware->alternateFunction); + const uint8_t timerIndex = getTimerIndex(timer); + const bool configureTimer = (timerIndex == dmaMotorTimerCount-1); - __DMA1_CLK_ENABLE(); + IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction); - RCC_ClockCmd(timerRCC(timer), ENABLE); + if (configureTimer) { + LL_TIM_InitTypeDef init; + LL_TIM_StructInit(&init); - motor->TimHandle.Instance = timerHardware->tim; - motor->TimHandle.Init.Prescaler = 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; + RCC_ClockCmd(timerRCC(timer), ENABLE); + LL_TIM_DisableCounter(timer); - if (HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK) { - /* Initialization Error */ - return; + init.Prescaler = (uint16_t)(lrintf((float) timerClock(timer) / getDshotHz(pwmProtocolType) + 0.01f) - 1); + init.Autoreload = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH; + init.ClockDivision = LL_TIM_CLOCKDIVISION_DIV1; + init.RepetitionCounter = 0; + init.CounterMode = LL_TIM_COUNTERMODE_UP; + LL_TIM_Init(timer, &init); } - // Note that a timer and an associated DMA are initialized more than once. - // To fix it, getTimerIndex must be expanded to return if a new timer has been requested. - // However, since the initialization is idempotent, it is left as is in a favor of flash space (for now). + LL_TIM_OC_StructInit(&oc_init); + oc_init.OCMode = LL_TIM_OCMODE_PWM1; + if (output & TIMER_OUTPUT_N_CHANNEL) { + oc_init.OCNState = LL_TIM_OCSTATE_ENABLE; + oc_init.OCNIdleState = LL_TIM_OCIDLESTATE_LOW; + oc_init.OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? LL_TIM_OCPOLARITY_LOW : LL_TIM_OCPOLARITY_HIGH; + } else { + oc_init.OCState = LL_TIM_OCSTATE_ENABLE; + oc_init.OCIdleState = LL_TIM_OCIDLESTATE_HIGH; + oc_init.OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? LL_TIM_OCPOLARITY_LOW : LL_TIM_OCPOLARITY_HIGH; + } + oc_init.CompareValue = 0; - motor->timer = &dmaMotorTimers[getTimerIndex(timer)]; + uint32_t channel; + switch (timerHardware->channel) { + case TIM_CHANNEL_1: channel = LL_TIM_CHANNEL_CH1; break; + case TIM_CHANNEL_2: channel = LL_TIM_CHANNEL_CH2; break; + case TIM_CHANNEL_3: channel = LL_TIM_CHANNEL_CH3; break; + case TIM_CHANNEL_4: channel = LL_TIM_CHANNEL_CH4; break; + } + LL_TIM_OC_Init(timer, channel, &oc_init); + LL_TIM_OC_EnablePreload(timer, channel); - /* Set the common dma handle parameters to be configured */ - 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.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; - motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; - motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; + if (output & TIMER_OUTPUT_N_CHANNEL) { + // @todo quick hack to get TIM_CCER_CCxNE from TIM_CCER_CCxE + LL_TIM_CC_EnableChannel(timer, 4 * channel); + } else { + LL_TIM_CC_EnableChannel(timer, channel); + } + + if (configureTimer) { + LL_TIM_EnableAllOutputs(timer); + LL_TIM_EnableARRPreload(timer); + LL_TIM_EnableCounter(timer); + } + + motor->timer = &dmaMotorTimers[timerIndex]; #ifdef USE_DSHOT_DMAR if (useBurstDshot) { - motor->timerDmaIndex = TIM_DMA_ID_UPDATE; - /* Set the DMAR specific dma handle parameters to be configured */ - motor->hdma_tim.Init.Channel = timerHardware->dmaTimUPChannel; - motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_ENABLE; + motor->timer->dmaBurstRef = dmaRef; - /* Set hdma_tim instance */ - motor->hdma_tim.Instance = timerHardware->dmaTimUPRef; + if (!configureTimer) { + motor->configured = true; + return; + } + } else +#endif + { + motor->timerDmaSource = timerDmaSource(timerHardware->channel); + motor->timer->timerDmaSources &= ~motor->timerDmaSource; + } - /* Link hdma_tim to hdma[x] (channelx) */ - __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim); + DMA_TypeDef *dma; + uint32_t stream; + if (dmaRef == DMA1_Stream0) { dma = DMA1; stream = LL_DMA_STREAM_0; } + else if (dmaRef == DMA1_Stream1) { dma = DMA1; stream = LL_DMA_STREAM_1; } + else if (dmaRef == DMA1_Stream2) { dma = DMA1; stream = LL_DMA_STREAM_2; } + else if (dmaRef == DMA1_Stream3) { dma = DMA1; stream = LL_DMA_STREAM_3; } + else if (dmaRef == DMA1_Stream4) { dma = DMA1; stream = LL_DMA_STREAM_4; } + else if (dmaRef == DMA1_Stream5) { dma = DMA1; stream = LL_DMA_STREAM_5; } + else if (dmaRef == DMA1_Stream6) { dma = DMA1; stream = LL_DMA_STREAM_6; } + else if (dmaRef == DMA1_Stream7) { dma = DMA1; stream = LL_DMA_STREAM_7; } + else if (dmaRef == DMA2_Stream0) { dma = DMA2; stream = LL_DMA_STREAM_0; } + else if (dmaRef == DMA2_Stream1) { dma = DMA2; stream = LL_DMA_STREAM_1; } + else if (dmaRef == DMA2_Stream2) { dma = DMA2; stream = LL_DMA_STREAM_2; } + else if (dmaRef == DMA2_Stream3) { dma = DMA2; stream = LL_DMA_STREAM_3; } + else if (dmaRef == DMA2_Stream4) { dma = DMA2; stream = LL_DMA_STREAM_4; } + else if (dmaRef == DMA2_Stream5) { dma = DMA2; stream = LL_DMA_STREAM_5; } + else if (dmaRef == DMA2_Stream6) { dma = DMA2; stream = LL_DMA_STREAM_6; } + else if (dmaRef == DMA2_Stream7) { dma = DMA2; stream = LL_DMA_STREAM_7; } + LL_DMA_DisableStream(dma, stream); + //CLEAR_BIT(dmaRef->CR, DMA_SxCR_EN); + LL_DMA_DeInit(dma, stream); + LL_DMA_StructInit(&dma_init); + +#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), motorIndex); + + dma_init.Channel = timerHardware->dmaTimUPChannel; + dma_init.MemoryOrM2MDstAddress = (uint32_t)motor->timer->dmaBurstBuffer; + dma_init.Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH; + dma_init.FIFOMode = LL_DMA_FIFOMODE_ENABLE; + dma_init.FIFOThreshold = LL_DMA_FIFOTHRESHOLD_FULL; + dma_init.MemBurst = LL_DMA_MBURST_SINGLE; + dma_init.PeriphBurst = LL_DMA_PBURST_SINGLE; + dma_init.PeriphOrM2MSrcAddress = (uint32_t)&timerHardware->tim->DMAR; + dma_init.NbData = (pwmProtocolType == PWM_TYPE_PROSHOT1000) ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; // XXX + dma_init.PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT; + dma_init.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT; + dma_init.PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_WORD; + dma_init.MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_WORD; + dma_init.Mode = LL_DMA_MODE_NORMAL; + dma_init.Priority = LL_DMA_PRIORITY_HIGH; } else #endif { - motor->timerDmaIndex = timerDmaIndex(timerHardware->channel); - motor->timer->timerDmaSources |= timerDmaSource(timerHardware->channel); - - /* Set the non-DMAR specific dma handle parameters to be configured */ - motor->hdma_tim.Init.Channel = timerHardware->dmaChannel; - motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - - /* Set hdma_tim instance */ - motor->hdma_tim.Instance = timerHardware->dmaRef; - - /* Link hdma_tim to hdma[x] (channelx) */ - __HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim); - dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex); + + dma_init.Channel = timerHardware->dmaChannel; + dma_init.MemoryOrM2MDstAddress = (uint32_t)motor->dmaBuffer; + dma_init.Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH; + dma_init.FIFOMode = LL_DMA_FIFOMODE_ENABLE; + dma_init.FIFOThreshold = LL_DMA_FIFOTHRESHOLD_1_4; + dma_init.MemBurst = LL_DMA_MBURST_SINGLE; + dma_init.PeriphBurst = LL_DMA_PBURST_SINGLE; + dma_init.PeriphOrM2MSrcAddress = (uint32_t)timerChCCR(timerHardware); + dma_init.NbData = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; + dma_init.PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT; + dma_init.MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT; + dma_init.PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_WORD; + dma_init.MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_WORD; + dma_init.Mode = LL_DMA_MODE_NORMAL; + dma_init.Priority = LL_DMA_PRIORITY_HIGH; } - /* Initialize TIMx DMA handle */ - if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaIndex]) != HAL_OK) { - /* Initialization Error */ - return; - } - - TIM_OC_InitTypeDef TIM_OCInitStructure; - - /* PWM1 Mode configuration: Channel1 */ - TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1; - 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; - - if (HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK) { - /* Configuration Error */ - return; - } - -#ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - /* Enable the Output compare channel */ - uint32_t channels = 0; - if(output & TIMER_OUTPUT_N_CHANNEL) { - switch(motor->timerHardware->channel) { - case TIM_CHANNEL_1: - channels = LL_TIM_CHANNEL_CH1N; - break; - case TIM_CHANNEL_2: - channels = LL_TIM_CHANNEL_CH2N; - break; - case TIM_CHANNEL_3: - channels = LL_TIM_CHANNEL_CH3N; - break; - } - } else { - switch(motor->timerHardware->channel) { - case TIM_CHANNEL_1: - channels = LL_TIM_CHANNEL_CH1; - break; - case TIM_CHANNEL_2: - channels = LL_TIM_CHANNEL_CH2; - break; - case TIM_CHANNEL_3: - channels = LL_TIM_CHANNEL_CH3; - break; - case TIM_CHANNEL_4: - channels = LL_TIM_CHANNEL_CH4; - break; - } - } - - LL_TIM_CC_EnableChannel(motor->timerHardware->tim, channels); - } else -#endif - { - if (output & TIMER_OUTPUT_N_CHANNEL) { - if (HAL_TIMEx_PWMN_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) { - /* Starting PWM generation Error */ - return; - } - } else { - if (HAL_TIM_PWM_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) { - /* Starting PWM generation Error */ - return; - } - } - } + // XXX Consolidate common settings in the next refactor + LL_DMA_Init(dma, stream, &dma_init); + LL_DMA_EnableIT_TC(dma, stream); motor->configured = true; } diff --git a/src/main/target/stm32f7xx_hal_conf.h b/src/main/target/stm32f7xx_hal_conf.h index 98a158d12..d84ddb9ed 100644 --- a/src/main/target/stm32f7xx_hal_conf.h +++ b/src/main/target/stm32f7xx_hal_conf.h @@ -161,7 +161,7 @@ #define PREFETCH_ENABLE 1U #define ART_ACCLERATOR_ENABLE 1U /* To enable instruction cache and prefetch */ #define INSTRUCTION_CACHE_ENABLE 1U -#define DATA_CACHE_ENABLE 0U +#define DATA_CACHE_ENABLE 1U /* ########################## Assert Selection ############################## */ /** diff --git a/src/main/target/system_stm32f7xx.c b/src/main/target/system_stm32f7xx.c index c739652fd..f44ef6232 100644 --- a/src/main/target/system_stm32f7xx.c +++ b/src/main/target/system_stm32f7xx.c @@ -304,7 +304,7 @@ void SystemInit(void) /* Configure the system clock to 216 MHz */ SystemClock_Config(); - if (SystemCoreClock != 216000000) { + if (SystemCoreClock != (PLL_N / PLL_P) * 1000000) { // There is a mismatch between the configured clock and the expected clock in portable.h while (1); } From 250d2965c2877cf5d2e0daf75baa2956a97ac2db Mon Sep 17 00:00:00 2001 From: Andrey Mironov Date: Tue, 20 Feb 2018 09:12:56 +0300 Subject: [PATCH 2/6] Fixed F3 burst DSHOT --- src/main/drivers/pwm_output.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 3e4dd3e03..f60af1b64 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -114,10 +114,10 @@ typedef struct { DMA_Channel_TypeDef *dmaBurstRef; #else DMA_Stream_TypeDef *dmaBurstRef; +#endif uint16_t dmaBurstLength; -#endif -#endif uint32_t dmaBurstBuffer[DSHOT_DMA_BUFFER_SIZE * 4]; +#endif uint16_t timerDmaSources; } motorDmaTimer_t; From 38935a1964b2ded36ffb2b1a482cf1b75e020429 Mon Sep 17 00:00:00 2001 From: Hydra Date: Fri, 2 Mar 2018 20:49:40 +0100 Subject: [PATCH 3/6] CF/BF - Fix SPI init on SPRacingF3OSD. --- src/main/osd_slave/osd_slave_init.c | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/src/main/osd_slave/osd_slave_init.c b/src/main/osd_slave/osd_slave_init.c index 0c2ad8735..61507c681 100644 --- a/src/main/osd_slave/osd_slave_init.c +++ b/src/main/osd_slave/osd_slave_init.c @@ -77,6 +77,7 @@ #include "pg/adc.h" #include "pg/bus_i2c.h" +#include "pg/bus_spi.h" #include "pg/pg.h" #include "pg/pg_ids.h" #include "pg/vcd.h" @@ -119,6 +120,20 @@ static IO_t busSwitchResetPin = IO_NONE; } #endif + +#ifdef USE_SPI +// Pre-initialize all CS pins to input with pull-up. +// It's sad that we can't do this with an initialized array, +// since we will be taking care of configurable CS pins shortly. + +void spiPreInit(void) +{ +#ifdef USE_MAX7456 + spiPreInitCs(IO_TAG(MAX7456_SPI_CS_PIN)); +#endif +} +#endif + void init(void) { #ifdef USE_HAL_DRIVER @@ -186,6 +201,11 @@ void init(void) #else #ifdef USE_SPI + spiPinConfigure(spiPinConfig()); + + // Initialize CS lines and keep them high + spiPreInit(); + #ifdef USE_SPI_DEVICE_1 spiInit(SPIDEV_1); #endif From 2c12a8fe527c2ef88ee2b337cbf329482168108a Mon Sep 17 00:00:00 2001 From: Hydra Date: Sat, 3 Mar 2018 01:29:35 +0100 Subject: [PATCH 4/6] CF/BF - Fix 'unused variable disableRunawayTakeoff' warning when building CJMCU. --- src/main/interface/msp.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c index 0b2b20a0c..551e56450 100644 --- a/src/main/interface/msp.c +++ b/src/main/interface/msp.c @@ -1773,6 +1773,9 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) { const uint8_t command = sbufReadU8(src); uint8_t disableRunawayTakeoff = 0; +#ifndef USE_RUNAWAY_TAKEOFF + UNUSED(disableRunawayTakeoff); +#endif if (sbufBytesRemaining(src)) { disableRunawayTakeoff = sbufReadU8(src); } From 64d6c86b28474c50535bc792734cff9b0afeb142 Mon Sep 17 00:00:00 2001 From: Hydra Date: Fri, 2 Mar 2018 23:19:59 +0100 Subject: [PATCH 5/6] Fix BEEBRAIN compilation. Broken since ee65eba88ddeff054769e8a41e2f1793a712806b --- src/main/target/NAZE/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c index 531c63ac6..9147c4f5d 100644 --- a/src/main/target/NAZE/config.c +++ b/src/main/target/NAZE/config.c @@ -89,7 +89,7 @@ void targetConfiguration(void) controlRateConfig->rcRates[FD_ROLL] = 100; controlRateConfig->rcRates[FD_PITCH] = 100; - controlRateConfig->rcRate[FD_YAW] = 110; + controlRateConfig->rcRates[FD_YAW] = 110; controlRateConfig->rcExpo[FD_ROLL] = 0; controlRateConfig->rcExpo[FD_PITCH] = 0; controlRateConfig->rates[FD_ROLL] = 77; From 2dcd50df0a46b45af8cdff82bf282bd566ea9487 Mon Sep 17 00:00:00 2001 From: J Blackman Date: Sat, 3 Mar 2018 20:25:57 +1100 Subject: [PATCH 6/6] Updated notice on 3.3 support for STM32F1 (#5360) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index aceda9ef4..e24e6c01e 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -![BetaFlight Notice, version 3.2 will be the last version of Betaflight to support STM32F1 based flight controllers, this includes NAZE, CC3D (original) and CJMCU like flight controllers](https://raw.githubusercontent.com/wiki/betaflight/betaflight/images/betaflight/bf3_2_notice.png) +![BetaFlight Notice, version 3.3 has dropped support for STM32F1 based flight controllers, this includes NAZE, CC3D (original) and CJMCU like flight controllers](https://raw.githubusercontent.com/wiki/betaflight/betaflight/images/betaflight/stm32f1_support_notice.png) ![BetaFlight](https://raw.githubusercontent.com/wiki/betaflight/betaflight/images/betaflight/bf_logo.png)