From 1b1648d135cc215f3ea64db334f42124a301953a Mon Sep 17 00:00:00 2001 From: Jay Blackman Date: Tue, 10 Jun 2025 19:37:03 +1000 Subject: [PATCH] APM: Formatting changes for cleanup (#14431) * APM: Formatting changes for cleanup * Formatting inconsistency * Missed in first round * Adjusted as per @ledvinap --- src/platform/APM32/adc_apm32f4xx.c | 3 +- src/platform/APM32/apm32f4xx_ddl_ex.h | 9 +- src/platform/APM32/bus_i2c_apm32.c | 22 ++-- src/platform/APM32/bus_spi_apm32.c | 3 +- src/platform/APM32/dshot_bitbang.c | 25 +++-- src/platform/APM32/dshot_bitbang_ddl.c | 19 +--- src/platform/APM32/pwm_output_dshot_apm32.c | 98 +++++++++--------- src/platform/APM32/serial_uart_apm32.c | 100 ++++++++++--------- src/platform/APM32/serial_uart_apm32f4xx.c | 2 + src/platform/APM32/system_apm32f4xx.c | 5 +- src/platform/APM32/timer_apm32.c | 81 +++++++++------ src/platform/APM32/transponder_ir_io_apm32.c | 1 + 12 files changed, 199 insertions(+), 169 deletions(-) diff --git a/src/platform/APM32/adc_apm32f4xx.c b/src/platform/APM32/adc_apm32f4xx.c index f577804602..38004b23be 100644 --- a/src/platform/APM32/adc_apm32f4xx.c +++ b/src/platform/APM32/adc_apm32f4xx.c @@ -270,8 +270,7 @@ void adcInit(const adcConfig_t *config) adcInitDevice(&adcInternal, 2); DDL_ADC_Enable(adcInternal.ADCx); adcInitInternalInjected(&adcInternal); - } - else { + } else { // Initialize for injected conversion adcInitInternalInjected(&adc); } diff --git a/src/platform/APM32/apm32f4xx_ddl_ex.h b/src/platform/APM32/apm32f4xx_ddl_ex.h index 187448df8d..30d53da2ac 100644 --- a/src/platform/APM32/apm32f4xx_ddl_ex.h +++ b/src/platform/APM32/apm32f4xx_ddl_ex.h @@ -31,10 +31,12 @@ __STATIC_INLINE void DDL_EX_TMR_DisableIT(TMR_TypeDef *TMRx, uint32_t Sources) { CLEAR_BIT(TMRx->DIEN, Sources); } + __STATIC_INLINE void DDL_EX_TMR_EnableIT(TMR_TypeDef *TMRx, uint32_t Sources) { SET_BIT(TMRx->DIEN, Sources); } + __STATIC_INLINE uint32_t DDL_EX_DMA_Stream_to_Stream(DMA_Stream_TypeDef *DMAx_Streamy) { STATIC_ASSERT(DMA1_Stream0_BASE - DMA1_BASE == sizeof(DMA_TypeDef), DMA_TypeDef_has_padding); @@ -45,11 +47,13 @@ __STATIC_INLINE uint32_t DDL_EX_DMA_Stream_to_Stream(DMA_Stream_TypeDef *DMAx_St return (((uint32_t) DMAx_Streamy & 0XFF) - firstStreamOffset) / streamSize; } + __STATIC_INLINE DMA_TypeDef *DDL_EX_DMA_Stream_to_DMA(DMA_Stream_TypeDef *DMAx_Streamy) { // clear stream address return (DMA_TypeDef *) (((uint32_t) DMAx_Streamy) & ((uint32_t) ~0XFF)); } + __STATIC_INLINE uint32_t DDL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy) { DMA_TypeDef *DMA = DDL_EX_DMA_Stream_to_DMA(DMAx_Streamy); @@ -57,6 +61,7 @@ __STATIC_INLINE uint32_t DDL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy) return DDL_DMA_DeInit(DMA, Stream); } + __STATIC_INLINE uint32_t DDL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, DDL_DMA_InitTypeDef *DMA_InitStruct) { DMA_TypeDef *DMA = DDL_EX_DMA_Stream_to_DMA(DMAx_Streamy); @@ -64,6 +69,7 @@ __STATIC_INLINE uint32_t DDL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, DDL_D return DDL_DMA_Init(DMA, Stream, DMA_InitStruct); } + __STATIC_INLINE void DDL_EX_DMA_SetDataLength(DMA_Stream_TypeDef* DMAx_Streamy, uint32_t NbData) { MODIFY_REG(DMAx_Streamy->NDATA, DMA_NDATAx, NbData); @@ -81,6 +87,7 @@ __STATIC_INLINE void DDL_EX_DMA_EnableResource(DMA_Stream_TypeDef *DMAx_Streamy) { SET_BIT(DMAx_Streamy->SCFG, DMA_SCFGx_EN); } + __STATIC_INLINE void DDL_EX_DMA_DisableResource(DMA_Stream_TypeDef *DMAx_Streamy) { CLEAR_BIT(DMAx_Streamy->SCFG, DMA_SCFGx_EN); @@ -94,4 +101,4 @@ __STATIC_INLINE void DDL_EX_DMA_EnableIT_TC(DMA_Stream_TypeDef *DMAx_Streamy) __STATIC_INLINE void DDL_EX_TMR_CC_EnableNChannel(TMR_TypeDef *TMRx, uint32_t Channel) { DDL_TMR_CC_EnableChannel(TMRx, 4 * Channel); -} \ No newline at end of file +} diff --git a/src/platform/APM32/bus_i2c_apm32.c b/src/platform/APM32/bus_i2c_apm32.c index 3b51cee474..147e5e986a 100644 --- a/src/platform/APM32/bus_i2c_apm32.c +++ b/src/platform/APM32/bus_i2c_apm32.c @@ -76,7 +76,7 @@ static volatile uint16_t i2cErrorCount = 0; static bool i2cHandleHardwareFailure(I2CDevice device) { - (void)device; + UNUSED(device); i2cErrorCount++; // reinit peripheral + clock out garbage //i2cInit(device); @@ -103,13 +103,15 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) HAL_StatusTypeDef status; - if (reg_ == 0xFF) + if (reg_ == 0xFF) { status = DAL_I2C_Master_Transmit(pHandle ,addr_ << 1, &data, 1, I2C_TIMEOUT_SYS_TICKS); - else + } else { status = DAL_I2C_Mem_Write(pHandle ,addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT, &data, 1, I2C_TIMEOUT_SYS_TICKS); + } - if (status != DAL_OK) + if (status != DAL_OK) { return i2cHandleHardwareFailure(device); + } return true; } @@ -135,8 +137,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, return false; } - if (status != DAL_OK) - { + if (status != DAL_OK) { return i2cHandleHardwareFailure(device); } @@ -158,10 +159,11 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t DAL_StatusTypeDef status; - if (reg_ == 0xFF) + if (reg_ == 0xFF) { status = DAL_I2C_Master_Receive(pHandle ,addr_ << 1, buf, len, I2C_TIMEOUT_SYS_TICKS); - else + } else { status = DAL_I2C_Mem_Read(pHandle, addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,buf, len, I2C_TIMEOUT_SYS_TICKS); + } if (status != DAL_OK) { return i2cHandleHardwareFailure(device); @@ -206,8 +208,7 @@ bool i2cBusy(I2CDevice device, bool *error) *error = pHandle->ErrorCode; } - if (pHandle->State == DAL_I2C_STATE_READY) - { + if (pHandle->State == DAL_I2C_STATE_READY) { if (__DAL_I2C_GET_FLAG(pHandle, I2C_FLAG_BUSY) == SET) { return true; @@ -218,5 +219,4 @@ bool i2cBusy(I2CDevice device, bool *error) return true; } - #endif diff --git a/src/platform/APM32/bus_spi_apm32.c b/src/platform/APM32/bus_spi_apm32.c index 2b9a484975..6c58c5e8da 100644 --- a/src/platform/APM32/bus_spi_apm32.c +++ b/src/platform/APM32/bus_spi_apm32.c @@ -347,8 +347,7 @@ FAST_CODE void spiSequenceStart(const extDevice_t *dev) IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->sckAF); DDL_SPI_SetClockPhase(instance, DDL_SPI_PHASE_1EDGE); DDL_SPI_SetClockPolarity(instance, DDL_SPI_POLARITY_LOW); - } - else { + } else { IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->sckAF); DDL_SPI_SetClockPhase(instance, DDL_SPI_PHASE_2EDGE); DDL_SPI_SetClockPolarity(instance, DDL_SPI_POLARITY_HIGH); diff --git a/src/platform/APM32/dshot_bitbang.c b/src/platform/APM32/dshot_bitbang.c index cf971adf97..caec5e0bec 100644 --- a/src/platform/APM32/dshot_bitbang.c +++ b/src/platform/APM32/dshot_bitbang.c @@ -450,14 +450,15 @@ static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorProtocolTypes_e pwmP bbGpioSetup(&bbMotors[motorIndex]); + do { #ifdef USE_DSHOT_TELEMETRY if (useDshotTelemetry) { bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_INVERTED); - } else -#endif - { - bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_NONINVERTED); + break; } +#endif + bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_NONINVERTED); + } while (false); bbSwitchToOutput(bbPort); @@ -577,14 +578,15 @@ static void bbWriteInt(uint8_t motorIndex, uint16_t value) bbPort_t *bbPort = bbmotor->bbPort; + do { #ifdef USE_DSHOT_TELEMETRY - if (useDshotTelemetry) { - bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_INVERTED); - } else + if (useDshotTelemetry) { + bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_INVERTED); + break; + } #endif - { bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_NONINVERTED); - } + } while (false); } static void bbWrite(uint8_t motorIndex, float value) @@ -614,11 +616,8 @@ static void bbUpdateComplete(void) bbPort->inputActive = false; bbSwitchToOutput(bbPort); } - } else -#endif - { - // Nothing to do } +#endif bbDMA_Cmd(bbPort, ENABLE); } diff --git a/src/platform/APM32/dshot_bitbang_ddl.c b/src/platform/APM32/dshot_bitbang_ddl.c index dc7301c491..6e2eeff13b 100644 --- a/src/platform/APM32/dshot_bitbang_ddl.c +++ b/src/platform/APM32/dshot_bitbang_ddl.c @@ -56,23 +56,12 @@ void bbGpioSetup(bbMotor_t *bbMotor) bbPort->gpioModeInput |= (DDL_GPIO_MODE_INPUT << (pinIndex * 2)); bbPort->gpioModeOutput |= (DDL_GPIO_MODE_OUTPUT << (pinIndex * 2)); + bool inverted = false; #ifdef USE_DSHOT_TELEMETRY - if (useDshotTelemetry) { - bbPort->gpioIdleBSRR |= (1 << pinIndex); // BS (lower half) - } else + inverted = true; #endif - { - bbPort->gpioIdleBSRR |= (1 << (pinIndex + 16)); // BR (higher half) - } - -#ifdef USE_DSHOT_TELEMETRY - if (useDshotTelemetry) { - IOWrite(bbMotor->io, 1); - } else -#endif - { - IOWrite(bbMotor->io, 0); - } + bbPort->gpioIdleBSRR |= (1 << pinIndex) + (inverted ? 0 : 16); // write BITSET or BITRESET half of BSRR + IOWrite(bbMotor->io, inverted); } void bbTimerChannelInit(bbPort_t *bbPort) diff --git a/src/platform/APM32/pwm_output_dshot_apm32.c b/src/platform/APM32/pwm_output_dshot_apm32.c index 203df9fefc..57010f08e8 100644 --- a/src/platform/APM32/pwm_output_dshot_apm32.c +++ b/src/platform/APM32/pwm_output_dshot_apm32.c @@ -133,18 +133,19 @@ FAST_CODE void pwmCompleteDshotMotorUpdate(void) } for (int i = 0; i < dmaMotorTimerCount; i++) { + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - xDDL_EX_DMA_SetDataLength(dmaMotorTimers[i].dmaBurstRef, dmaMotorTimers[i].dmaBurstLength); - xDDL_EX_DMA_EnableResource(dmaMotorTimers[i].dmaBurstRef); + if (useBurstDshot) { + xDDL_EX_DMA_SetDataLength(dmaMotorTimers[i].dmaBurstRef, dmaMotorTimers[i].dmaBurstLength); + xDDL_EX_DMA_EnableResource(dmaMotorTimers[i].dmaBurstRef); - /* configure the DMA Burst Mode */ - DDL_TMR_ConfigDMABurst(dmaMotorTimers[i].timer, DDL_TMR_DMABURST_BASEADDR_CC1, DDL_TMR_DMABURST_LENGTH_4TRANSFERS); - /* Enable the TIM DMA Request */ - DDL_TMR_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer); - } else + /* configure the DMA Burst Mode */ + DDL_TMR_ConfigDMABurst(dmaMotorTimers[i].timer, DDL_TMR_DMABURST_BASEADDR_CC1, DDL_TMR_DMABURST_LENGTH_4TRANSFERS); + /* Enable the TIM DMA Request */ + DDL_TMR_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer); + break; + } #endif - { DDL_TMR_DisableARRPreload(dmaMotorTimers[i].timer); dmaMotorTimers[i].timer->AUTORLD = dmaMotorTimers[i].outputPeriod; @@ -153,7 +154,7 @@ FAST_CODE void pwmCompleteDshotMotorUpdate(void) /* Enable channel DMA requests */ DDL_EX_TMR_EnableIT(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources); dmaMotorTimers[i].timerDmaSources = 0; - } + } while (false); } } @@ -164,16 +165,17 @@ FAST_CODE static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) #ifdef USE_DSHOT_TELEMETRY dshotDMAHandlerCycleCounters.irqAt = getCycleCounter(); #endif + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - xDDL_EX_DMA_DisableResource(motor->timerHardware->dmaTimUPRef); - DDL_TMR_DisableDMAReq_UPDATE(motor->timerHardware->tim); - } else + if (useBurstDshot) { + xDDL_EX_DMA_DisableResource(motor->timerHardware->dmaTimUPRef); + DDL_TMR_DisableDMAReq_UPDATE(motor->timerHardware->tim); + break; + } #endif - { xDDL_EX_DMA_DisableResource(motor->dmaRef); DDL_EX_TMR_DisableIT(motor->timerHardware->tim, motor->timerDmaSource); - } + } while (false); #ifdef USE_DSHOT_TELEMETRY if (useDshotTelemetry) { @@ -228,21 +230,22 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(dmaRef); bool dmaIsConfigured = false; + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - const resourceOwner_t *owner = dmaGetOwner(dmaIdentifier); - if (owner->owner == OWNER_TIMUP && owner->resourceIndex == timerGetTIMNumber(timerHardware->tim)) { - dmaIsConfigured = true; - } else if (!dmaAllocate(dmaIdentifier, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim))) { - return false; + if (useBurstDshot) { + const resourceOwner_t *owner = dmaGetOwner(dmaIdentifier); + if (owner->owner == OWNER_TIMUP && owner->resourceIndex == timerGetTIMNumber(timerHardware->tim)) { + dmaIsConfigured = true; + } else if (!dmaAllocate(dmaIdentifier, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim))) { + return false; + } + break; } - } else #endif - { if (!dmaAllocate(dmaIdentifier, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex))) { return false; } - } + } while (false); motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; motor->dmaRef = dmaRef; @@ -312,18 +315,19 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m } motor->llChannel = channel; + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - motor->timer->dmaBurstRef = dmaRef; + if (useBurstDshot) { + motor->timer->dmaBurstRef = dmaRef; #ifdef USE_DSHOT_TELEMETRY - motor->dmaRef = dmaRef; + motor->dmaRef = dmaRef; #endif - } else + break; + } #endif - { motor->timerDmaSource = timerDmaSource(timerHardware->channel); motor->timer->timerDmaSources &= ~motor->timerDmaSource; - } + } while (false); if (!dmaIsConfigured) { xDDL_EX_DMA_DisableResource(dmaRef); @@ -333,24 +337,25 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m } DDL_DMA_StructInit(&DMAINIT); + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - motor->timer->dmaBurstBuffer = &dshotBurstDmaBuffer[timerIndex][0]; + if (useBurstDshot) { + motor->timer->dmaBurstBuffer = &dshotBurstDmaBuffer[timerIndex][0]; - DMAINIT.Channel = dmaChannel; - DMAINIT.MemoryOrM2MDstAddress = (uint32_t)motor->timer->dmaBurstBuffer; - DMAINIT.FIFOThreshold = DDL_DMA_FIFOTHRESHOLD_FULL; - DMAINIT.PeriphOrM2MSrcAddress = (uint32_t)&timerHardware->tim->DMAR; - } else + DMAINIT.Channel = dmaChannel; + DMAINIT.MemoryOrM2MDstAddress = (uint32_t)motor->timer->dmaBurstBuffer; + DMAINIT.FIFOThreshold = DDL_DMA_FIFOTHRESHOLD_FULL; + DMAINIT.PeriphOrM2MSrcAddress = (uint32_t)&timerHardware->tim->DMAR; + break; + } #endif - { motor->dmaBuffer = &dshotDmaBuffer[motorIndex][0]; DMAINIT.Channel = dmaChannel; DMAINIT.MemoryOrM2MDstAddress = (uint32_t)motor->dmaBuffer; DMAINIT.FIFOThreshold = DDL_DMA_FIFOTHRESHOLD_1_4; DMAINIT.PeriphOrM2MSrcAddress = (uint32_t)timerChCCR(timerHardware); - } + } while (false); DMAINIT.Direction = DDL_DMA_DIRECTION_MEMORY_TO_PERIPH; DMAINIT.FIFOMode = DDL_DMA_FIFOMODE_ENABLE; @@ -380,16 +385,17 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m pwmDshotSetDirectionOutput(motor, &OCINIT, &DMAINIT); #endif + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - if (!dmaIsConfigured) { - dmaSetHandler(dmaIdentifier, motor_DMA_IRQHandler, NVIC_PRIO_DSHOT_DMA, motor->index); + if (useBurstDshot) { + if (!dmaIsConfigured) { + dmaSetHandler(dmaIdentifier, motor_DMA_IRQHandler, NVIC_PRIO_DSHOT_DMA, motor->index); + } + break; } - } else #endif - { dmaSetHandler(dmaIdentifier, motor_DMA_IRQHandler, NVIC_PRIO_DSHOT_DMA, motor->index); - } + } while (false); DDL_TMR_OC_Init(timer, channel, &OCINIT); DDL_TMR_OC_EnablePreload(timer, channel); diff --git a/src/platform/APM32/serial_uart_apm32.c b/src/platform/APM32/serial_uart_apm32.c index eb6da0f291..64ac4a3da3 100644 --- a/src/platform/APM32/serial_uart_apm32.c +++ b/src/platform/APM32/serial_uart_apm32.c @@ -82,35 +82,37 @@ void uartReconfigure(uartPort_t *uartPort) // Receive DMA or IRQ if (uartPort->port.mode & MODE_RX) { + do { #ifdef USE_DMA - if (uartPort->rxDMAResource) { - uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource; - uartPort->txDMAHandle.Init.Channel = uartPort->rxDMAChannel; - uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY; - uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; - uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE; - uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; - uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; - uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR; + if (uartPort->rxDMAResource) { + uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource; + uartPort->txDMAHandle.Init.Channel = uartPort->rxDMAChannel; + uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY; + uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; + uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE; + uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR; #if defined(APM32F4) - uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; - uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; - uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; + uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; + uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; + uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; #endif - uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; + uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - DAL_DMA_DeInit(&uartPort->rxDMAHandle); - DAL_DMA_Init(&uartPort->rxDMAHandle); - /* Associate the initialized DMA handle to the UART handle */ - __DAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle); + DAL_DMA_DeInit(&uartPort->rxDMAHandle); + DAL_DMA_Init(&uartPort->rxDMAHandle); + /* Associate the initialized DMA handle to the UART handle */ + __DAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle); - DAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize); + DAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize); - uartPort->rxDMAPos = __DAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle); - } else + uartPort->rxDMAPos = __DAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle); + break; + } #endif - { + /* Enable the UART Parity Error Interrupt */ SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_PEIEN); @@ -122,44 +124,44 @@ void uartReconfigure(uartPort_t *uartPort) /* Enable Idle Line detection */ SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_IDLEIEN); - } + } while(false); } // Transmit DMA or IRQ if (uartPort->port.mode & MODE_TX) { + do { #ifdef USE_DMA - if (uartPort->txDMAResource) { - uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource; - uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel; - uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH; - uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; - uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE; - uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; - uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; - uartPort->txDMAHandle.Init.Mode = DMA_NORMAL; - uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; - uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; - uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; - uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; + if (uartPort->txDMAResource) { + uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource; + uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel; + uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH; + uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; + uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE; + uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + uartPort->txDMAHandle.Init.Mode = DMA_NORMAL; + uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; + uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; + uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; + uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - DAL_DMA_DeInit(&uartPort->txDMAHandle); - DAL_StatusTypeDef status = DAL_DMA_Init(&uartPort->txDMAHandle); - if (status != DAL_OK) { - while (1); + DAL_DMA_DeInit(&uartPort->txDMAHandle); + DAL_StatusTypeDef status = DAL_DMA_Init(&uartPort->txDMAHandle); + if (status != DAL_OK) { + while (1); + } + /* Associate the initialized DMA handle to the UART handle */ + __DAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle); + + __DAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0); + break; } - /* Associate the initialized DMA handle to the UART handle */ - __DAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle); - - __DAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0); - } else #endif - { - /* Enable the UART Transmit Data Register Empty Interrupt */ SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_TXBEIEN); SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_TXCIEN); - } + } while(false); } } diff --git a/src/platform/APM32/serial_uart_apm32f4xx.c b/src/platform/APM32/serial_uart_apm32f4xx.c index 7978e6315e..2df52a9ffd 100644 --- a/src/platform/APM32/serial_uart_apm32f4xx.c +++ b/src/platform/APM32/serial_uart_apm32f4xx.c @@ -269,10 +269,12 @@ void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor) } handleUsartTxDma(s); } + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF)) { DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF); } + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF)) { DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF); diff --git a/src/platform/APM32/system_apm32f4xx.c b/src/platform/APM32/system_apm32f4xx.c index 0bf5b42231..75945bd924 100644 --- a/src/platform/APM32/system_apm32f4xx.c +++ b/src/platform/APM32/system_apm32f4xx.c @@ -121,10 +121,11 @@ void enableGPIOPowerUsageAndNoiseReductions(void) bool isMPUSoftReset(void) { - if (cachedRccCsrValue & RCM_CSTS_SWRSTFLG) + if (cachedRccCsrValue & RCM_CSTS_SWRSTFLG) { return true; - else + } else { return false; + } } void systemInit(void) diff --git a/src/platform/APM32/timer_apm32.c b/src/platform/APM32/timer_apm32.c index 5e52ec654c..710ebc509a 100644 --- a/src/platform/APM32/timer_apm32.c +++ b/src/platform/APM32/timer_apm32.c @@ -340,7 +340,9 @@ TMR_HandleTypeDef* timerFindTimerHandle(TMR_TypeDef *tim) void timerReconfigureTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) { TMR_HandleTypeDef* handle = timerFindTimerHandle(tim); - if (handle == NULL) return; + if (handle == NULL) { + return; + } handle->Init.Period = (period - 1) & 0xffff; // AKA TIMx_ARR handle->Init.Prescaler = (timerClock(tim) / hz) - 1; @@ -351,7 +353,9 @@ void timerReconfigureTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) void configTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) { TMR_HandleTypeDef* handle = timerFindTimerHandle(tim); - if (handle == NULL) return; + if (handle == NULL) { + return; + } if (handle->Instance == tim) { // already configured @@ -368,8 +372,7 @@ void configTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) handle->Init.RepetitionCounter = 0x0000; DAL_TMR_Base_Init(handle); - if (tim == TMR1 || tim == TMR2 || tim == TMR3 || tim == TMR4 || tim == TMR5 || tim == TMR8 || tim == TMR9) - { + if (tim == TMR1 || tim == TMR2 || tim == TMR3 || tim == TMR4 || tim == TMR5 || tim == TMR8 || tim == TMR9) { TMR_ClockConfigTypeDef sClockSourceConfig; memset(&sClockSourceConfig, 0, sizeof(sClockSourceConfig)); sClockSourceConfig.ClockSource = TMR_CLOCKSOURCE_INTERNAL; @@ -402,7 +405,6 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui timerNVICConfigure(irq); // HACK - enable second IRQ on timers that need it switch (irq) { - case TMR1_CC_IRQn: timerNVICConfigure(TMR1_UP_TMR10_IRQn); break; @@ -421,13 +423,16 @@ void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriori return; } unsigned channel = timHw - TIMER_HARDWARE; - if (channel >= TIMER_CHANNEL_COUNT) + if (channel >= TIMER_CHANNEL_COUNT) { return; + } timerChannelInfo[channel].type = type; unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } + if (irqPriority < timerInfo[timer].priority) { // it would be better to set priority in the end, but current startup sequence is not ready configTimeBase(usedTimers[timer], 0, 1); @@ -476,10 +481,11 @@ static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const TMR_TypeDef * *chain = NULL; } // enable or disable IRQ - if (cfg->overflowCallbackActive) + if (cfg->overflowCallbackActive) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TMR_IT_UPDATE); - else + } else { __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TMR_IT_UPDATE); + } } // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive @@ -490,14 +496,17 @@ void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *e return; } uint8_t channelIndex = lookupChannelIndex(timHw->channel); - if (edgeCallback == NULL) // disable irq before changing callback to NULL + if (edgeCallback == NULL) { // disable irq before changing callback to NULL __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); + } + // setup callback info timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback; timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback; // enable channel IRQ - if (edgeCallback) + if (edgeCallback) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); + } timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim); } @@ -525,10 +534,13 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_ uint16_t chHi = timHw->channel | TMR_CHANNEL_2; // upper channel uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel - if (edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL + if (edgeCallbackLo == NULL) { // disable irq before changing setting callback to NULL __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chLo)); - if (edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL + } + + if (edgeCallbackHi == NULL) { // disable irq before changing setting callback to NULL __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chHi)); + } // setup callback info timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallbackLo; @@ -541,6 +553,7 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_ __DAL_TMR_CLEAR_FLAG(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chLo)); __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chLo)); } + if (edgeCallbackHi) { __DAL_TMR_CLEAR_FLAG(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chHi)); __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chHi)); @@ -561,10 +574,11 @@ void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newStat return; } - if (newState) + if (newState) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TMR_CHANNEL_2)); - else + } else { __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TMR_CHANNEL_2)); + } } //// enable or disable IRQ @@ -580,10 +594,11 @@ void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState) return; } - if (newState) + if (newState) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); - else + } else { __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); + } } // clear Compare/Capture flag for channel @@ -623,9 +638,11 @@ static unsigned getFilter(unsigned ticks) 16*5, 16*6, 16*8, 32*5, 32*6, 32*8 }; - for (unsigned i = 1; i < ARRAYLEN(ftab); i++) - if (ftab[i] > ticks) + for (unsigned i = 1; i < ARRAYLEN(ftab); i++) { + if (ftab[i] > ticks) { return i - 1; + } + } return 0x0f; } @@ -633,8 +650,9 @@ static unsigned getFilter(unsigned ticks) void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks) { unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } TMR_IC_InitTypeDef TIM_ICInitStructure; @@ -650,8 +668,9 @@ void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks) { unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } TMR_IC_InitTypeDef TIM_ICInitStructure; bool directRising = (timHw->channel & TMR_CHANNEL_2) ? !polarityRising : polarityRising; @@ -695,8 +714,9 @@ volatile timCCR_t* timerChCCR(const timerHardware_t *timHw) void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh) { unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } TMR_OC_InitTypeDef TIM_OCInitStructure; @@ -1000,7 +1020,9 @@ void timerInit(void) void timerStart(TMR_TypeDef *tim) { TMR_HandleTypeDef* handle = timerFindTimerHandle(tim); - if (handle == NULL) return; + if (handle == NULL) { + return; + } __DAL_TMR_ENABLE(handle); } @@ -1135,13 +1157,16 @@ DAL_StatusTypeDef DMA_SetCurrDataCounter(TMR_HandleTypeDef *htim, uint32_t Chann { if ((htim->State == DAL_TMR_STATE_BUSY)) { return DAL_BUSY; - } else if ((htim->State == DAL_TMR_STATE_READY)) { - if (((uint32_t) pData == 0) && (Length > 0)) { - return DAL_ERROR; - } else { - htim->State = DAL_TMR_STATE_BUSY; + } else { + if ((htim->State == DAL_TMR_STATE_READY)) { + if (((uint32_t) pData == 0) && (Length > 0)) { + return DAL_ERROR; + } else { + htim->State = DAL_TMR_STATE_BUSY; + } } } + switch (Channel) { case TMR_CHANNEL_1: { /* Set the DMA Period elapsed callback */ diff --git a/src/platform/APM32/transponder_ir_io_apm32.c b/src/platform/APM32/transponder_ir_io_apm32.c index ff4d778736..29a6786a80 100644 --- a/src/platform/APM32/transponder_ir_io_apm32.c +++ b/src/platform/APM32/transponder_ir_io_apm32.c @@ -165,6 +165,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder) /* Configuration Error */ return; } + if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) { if (DAL_TMREx_PWMN_Start(&TmrHandle, timerChannel) != DAL_OK) { /* Starting PWM generation Error */