uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE]; s = &uartPort2; s->port.vTable = uartVTable; s->port.baudRate = baudRate; s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.rxBuffer = rx2Buffer; s->port.txBuffer = tx2Buffer; s->USARTx = USART2; #ifdef USE_UART2_RX_DMA s->rxDMAChannel = DMA1_Channel6; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; #endif #ifdef USE_UART2_TX_DMA s->txDMAChannel = DMA1_Channel7; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; #endif RCC_ClockCmd(RCC_APB1(USART2), ENABLE); #if defined(USE_UART2_TX_DMA) || defined(USE_UART2_RX_DMA) RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); #endif serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7, 2); #ifdef USE_UART2_TX_DMA // DMA TX Interrupt dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, (uint32_t)&uartPort2); #endif #ifndef USE_UART2_RX_DMA NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_RXDMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2_RXDMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); #endif return s; }
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx5Buffer[UART5_RX_BUFFER_SIZE]; static volatile uint8_t tx5Buffer[UART5_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; s = &uartPort5; s->port.vTable = uartVTable; s->port.baudRate = baudRate; s->port.rxBufferSize = UART5_RX_BUFFER_SIZE; s->port.txBufferSize = UART5_TX_BUFFER_SIZE; s->port.rxBuffer = rx5Buffer; s->port.txBuffer = tx5Buffer; s->USARTx = UART5; RCC_ClockCmd(RCC_APB1(UART5), ENABLE); serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5, 5); NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART5); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART5); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); return s; }
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ) uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; s = &uartPort2; s->port.vTable = uartVTable; s->port.baudRate = baudRate; s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.rxBuffer = rx2Buffer; s->port.txBuffer = tx2Buffer; s->USARTx = USART2; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; RCC_ClockCmd(RCC_APB1(USART2), ENABLE); // UART2_TX PA2 // UART2_RX PA3 if (options & SERIAL_BIDIR) { IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP); } if (mode & MODE_RX) { IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL_RX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU); } } // RX/TX Interrupt NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); return s; }
void adcInit(const adcConfig_t *config) { uint8_t configuredAdcChannels = 0; memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig)); if (config->vbat.enabled) { adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag; } if (config->rssi.enabled) { adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL; } if (config->external1.enabled) { adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL; } if (config->current.enabled) { adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL; } ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; const adcDevice_t adc = adcHardware[device]; bool adcActive = false; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcOperatingConfig[i].tag) continue; adcActive = true; IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0); IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0)); adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag); adcOperatingConfig[i].dmaIndex = configuredAdcChannels++; adcOperatingConfig[i].sampleTime = ADC_SampleTime_239Cycles5; adcOperatingConfig[i].enabled = true; } if (!adcActive) { return; } RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) RCC_ClockCmd(adc.rccADC, ENABLE); dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC, 0); DMA_DeInit(adc.DMAy_Channelx); DMA_InitTypeDef DMA_InitStructure; DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_BufferSize = configuredAdcChannels; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_MemoryInc = configuredAdcChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure); DMA_Cmd(adc.DMAy_Channelx, ENABLE); ADC_InitTypeDef ADC_InitStructure; ADC_StructInit(&ADC_InitStructure); ADC_InitStructure.ADC_Mode = ADC_Mode_Independent; ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_NbrOfChannel = configuredAdcChannels; ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcOperatingConfig[i].enabled) { continue; } ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime); } ADC_DMACmd(adc.ADCx, ENABLE); ADC_Cmd(adc.ADCx, ENABLE); ADC_ResetCalibration(adc.ADCx); while (ADC_GetResetCalibrationStatus(adc.ADCx)); ADC_StartCalibration(adc.ADCx); while (ADC_GetCalibrationStatus(adc.ADCx)); ADC_SoftwareStartConvCmd(adc.ADCx, ENABLE); }
void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType) { motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; motor->timerHardware = timerHardware; TIM_TypeDef *timer = timerHardware->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_PULLUP), timerHardware->alternateFunction); __DMA1_CLK_ENABLE(); if (configureTimer) { RCC_ClockCmd(timerRCC(timer), ENABLE); uint32_t hz; switch (pwmProtocolType) { case(PWM_TYPE_DSHOT600): hz = MOTOR_DSHOT600_MHZ * 1000000; break; case(PWM_TYPE_DSHOT300): hz = MOTOR_DSHOT300_MHZ * 1000000; break; default: case(PWM_TYPE_DSHOT150): hz = MOTOR_DSHOT150_MHZ * 1000000; } motor->TimHandle.Instance = timerHardware->tim; motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1;; motor->TimHandle.Init.Period = MOTOR_BITLENGTH; motor->TimHandle.Init.RepetitionCounter = 0; motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK) { /* Initialization Error */ return; } } else { motor->TimHandle = dmaMotors[timerIndex].TimHandle; } switch (timerHardware->channel) { case TIM_CHANNEL_1: motor->timerDmaSource = TIM_DMA_ID_CC1; break; case TIM_CHANNEL_2: motor->timerDmaSource = TIM_DMA_ID_CC2; break; case TIM_CHANNEL_3: motor->timerDmaSource = TIM_DMA_ID_CC3; break; case TIM_CHANNEL_4: motor->timerDmaSource = TIM_DMA_ID_CC4; break; } dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource; /* Set the parameters to be configured */ motor->hdma_tim.Init.Channel = timerHardware->dmaChannel; 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.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; /* Set hdma_tim instance */ if(timerHardware->dmaStream == NULL) { /* Initialization Error */ return; } motor->hdma_tim.Instance = timerHardware->dmaStream; /* Link hdma_tim to hdma[x] (channelx) */ __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) { /* Initialization Error */ return; } TIM_OC_InitTypeDef TIM_OCInitStructure; /* PWM1 Mode configuration: Channel1 */ TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1; TIM_OCInitStructure.OCPolarity = TIM_OCPOLARITY_HIGH; TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET; TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET; 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; } }
bool hcsr04Detect(rangefinderDev_t *dev, const sonarConfig_t * rangefinderHardwarePins) { bool detected = false; #ifdef STM32F10X // enable AFIO for EXTI support RCC_ClockCmd(RCC_APB2(AFIO), ENABLE); #endif #if defined(STM32F3) || defined(STM32F4) RCC_ClockCmd(RCC_APB2(SYSCFG), ENABLE); // XXX Do we need this? #endif triggerIO = IOGetByTag(rangefinderHardwarePins->triggerTag); echoIO = IOGetByTag(rangefinderHardwarePins->echoTag); if (IOGetOwner(triggerIO) != OWNER_FREE) { return false; } if (IOGetOwner(echoIO) != OWNER_FREE) { return false; } // trigger pin IOInit(triggerIO, OWNER_SONAR_TRIGGER, 0); IOConfigGPIO(triggerIO, IOCFG_OUT_PP); IOLo(triggerIO); delay(100); // echo pin IOInit(echoIO, OWNER_SONAR_ECHO, 0); IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); // HC-SR04 echo line should be low by default and should return a response pulse when triggered if (IORead(echoIO) == false) { for (int i = 0; i < 5 && !detected; i++) { timeMs_t requestTime = millis(); hcsr04_start_reading(); while ((millis() - requestTime) < HCSR04_MinimumFiringIntervalMs) { if (IORead(echoIO) == true) { detected = true; break; } } } } if (detected) { // Hardware detected - configure the driver #ifdef USE_EXTI EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler); EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority! EXTIEnable(echoIO, true); #endif dev->delayMs = 100; dev->maxRangeCm = HCSR04_MAX_RANGE_CM; dev->detectionConeDeciDegrees = HCSR04_DETECTION_CONE_DECIDEGREES; dev->detectionConeExtendedDeciDegrees = HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES; dev->init = &hcsr04_init; dev->update = &hcsr04_update; dev->read = &hcsr04_get_distance; return true; } else { // Not detected - free resources IORelease(triggerIO); IORelease(echoIO); return false; } }
void spiInitDevice(SPIDevice device) { static SPI_InitTypeDef spiInit; spiDevice_t *spi = &(spiHardwareMap[device]); #ifdef SDCARD_SPI_INSTANCE if (spi->dev == SDCARD_SPI_INSTANCE) { spi->leadingEdge = true; } #endif #ifdef RX_SPI_INSTANCE if (spi->dev == RX_SPI_INSTANCE) { spi->leadingEdge = true; } #endif // Enable SPI clock RCC_ClockCmd(spi->rcc, ENABLE); RCC_ResetCmd(spi->rcc, ENABLE); IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1); IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); #if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); if (spi->nss) { IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af); } #endif #if defined(STM32F10X) IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG); IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG); IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG); if (spi->nss) { IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); } #endif SPI_HandleTypeDef Handle; Handle.Instance = spi->dev; // Init SPI hardware HAL_SPI_DeInit(&Handle); spiInit.Mode = SPI_MODE_MASTER; spiInit.Direction = SPI_DIRECTION_2LINES; spiInit.DataSize = SPI_DATASIZE_8BIT; spiInit.NSS = SPI_NSS_SOFT; spiInit.FirstBit = SPI_FIRSTBIT_MSB; spiInit.CRCPolynomial = 7; spiInit.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256; spiInit.CRCCalculation = SPI_CRCCALCULATION_DISABLE; spiInit.TIMode = SPI_TIMODE_DISABLED; if (spi->leadingEdge) { spiInit.CLKPolarity = SPI_POLARITY_LOW; spiInit.CLKPhase = SPI_PHASE_1EDGE; } else { spiInit.CLKPolarity = SPI_POLARITY_HIGH; spiInit.CLKPhase = SPI_PHASE_2EDGE; } Handle.Init = spiInit; #ifdef STM32F303xC // Configure for 8-bit reads. SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF); #endif if (HAL_SPI_Init(&Handle) == HAL_OK) { spiHandle[device].Handle = Handle; if (spi->nss) { IOHi(IOGetByTag(spi->nss)); } } }
static void adcInstanceInit(ADCDevice adcDevice) { ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; ADC_CommonInitTypeDef ADC_CommonInitStructure; adcDevice_t * adc = &adcHardware[adcDevice]; RCC_ClockCmd(adc->rccADC, ENABLE); RCC_ClockCmd(adc->rccDMA, ENABLE); DMA_DeInit(adc->DMAy_Channelx); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc->ADCx->DR; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues[adcDevice]; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_BufferSize = adc->usedChannelCount * ADC_AVERAGE_N_SAMPLES; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_MemoryInc = ((adc->usedChannelCount > 1) || (ADC_AVERAGE_N_SAMPLES > 1)) ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_Init(adc->DMAy_Channelx, &DMA_InitStructure); DMA_Cmd(adc->DMAy_Channelx, ENABLE); // calibrate ADC_VoltageRegulatorCmd(adc->ADCx, ENABLE); delay(10); ADC_SelectCalibrationMode(adc->ADCx, ADC_CalibrationMode_Single); ADC_StartCalibration(adc->ADCx); while (ADC_GetCalibrationStatus(adc->ADCx) != RESET); ADC_VoltageRegulatorCmd(adc->ADCx, DISABLE); ADC_CommonStructInit(&ADC_CommonInitStructure); ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; ADC_CommonInitStructure.ADC_Clock = ADC_Clock_SynClkModeDiv4; ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1; ADC_CommonInitStructure.ADC_DMAMode = ADC_DMAMode_Circular; ADC_CommonInitStructure.ADC_TwoSamplingDelay = 0; ADC_CommonInit(adc->ADCx, &ADC_CommonInitStructure); ADC_StructInit(&ADC_InitStructure); ADC_InitStructure.ADC_ContinuousConvMode = ADC_ContinuousConvMode_Enable; ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; ADC_InitStructure.ADC_ExternalTrigConvEvent = ADC_ExternalTrigConvEvent_0; ADC_InitStructure.ADC_ExternalTrigEventEdge = ADC_ExternalTrigEventEdge_None; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_OverrunMode = ADC_OverrunMode_Disable; ADC_InitStructure.ADC_AutoInjMode = ADC_AutoInjec_Disable; ADC_InitStructure.ADC_NbrOfRegChannel = adc->usedChannelCount; ADC_Init(adc->ADCx, &ADC_InitStructure); uint8_t rank = 1; for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) { if (!adcConfig[i].enabled || adcConfig[i].adcDevice != adcDevice) { continue; } ADC_RegularChannelConfig(adc->ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); } ADC_Cmd(adc->ADCx, ENABLE); while (!ADC_GetFlagStatus(adc->ADCx, ADC_FLAG_RDY)); ADC_DMAConfig(adc->ADCx, ADC_DMAMode_Circular); ADC_DMACmd(adc->ADCx, ENABLE); ADC_StartConversion(adc->ADCx); }
void i2cInit(I2CDevice device) { /*## Configure the I2C clock source. The clock is derived from the SYSCLK #*/ // RCC_PeriphCLKInitTypeDef RCC_PeriphCLKInitStruct; // RCC_PeriphCLKInitStruct.PeriphClockSelection = i2cHardwareMap[device].clk; // RCC_PeriphCLKInitStruct.I2c1ClockSelection = i2cHardwareMap[device].clk_src; // HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphCLKInitStruct); switch (device) { case I2CDEV_1: __HAL_RCC_I2C1_CLK_ENABLE(); break; case I2CDEV_2: __HAL_RCC_I2C2_CLK_ENABLE(); break; case I2CDEV_3: __HAL_RCC_I2C3_CLK_ENABLE(); break; case I2CDEV_4: __HAL_RCC_I2C4_CLK_ENABLE(); break; default: break; } if (device == I2CINVALID) return; i2cDevice_t *i2c; i2c = &(i2cHardwareMap[device]); //I2C_InitTypeDef i2cInit; IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device)); IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device)); // Enable RCC RCC_ClockCmd(i2c->rcc, ENABLE); i2cUnstick(scl, sda); // Init pins #ifdef STM32F7 IOConfigGPIOAF(scl, IOCFG_I2C, i2c->af); IOConfigGPIOAF(sda, IOCFG_I2C, i2c->af); #else IOConfigGPIO(scl, IOCFG_AF_OD); IOConfigGPIO(sda, IOCFG_AF_OD); #endif // Init I2C peripheral HAL_I2C_DeInit(&i2cHandle[device].Handle); i2cHandle[device].Handle.Instance = i2cHardwareMap[device].dev; /// TODO: HAL check if I2C timing is correct i2cHandle[device].Handle.Init.Timing = 0x00B01B59; //i2cHandle[device].Handle.Init.Timing = 0x00D00E28; /* (Rise time = 120ns, Fall time = 25ns) */ i2cHandle[device].Handle.Init.OwnAddress1 = 0x0; i2cHandle[device].Handle.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; i2cHandle[device].Handle.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; i2cHandle[device].Handle.Init.OwnAddress2 = 0x0; i2cHandle[device].Handle.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; i2cHandle[device].Handle.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; HAL_I2C_Init(&i2cHandle[device].Handle); /* Enable the Analog I2C Filter */ HAL_I2CEx_ConfigAnalogFilter(&i2cHandle[device].Handle,I2C_ANALOGFILTER_ENABLE); HAL_NVIC_SetPriority(i2cHardwareMap[device].er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER)); HAL_NVIC_EnableIRQ(i2cHardwareMap[device].er_irq); HAL_NVIC_SetPriority(i2cHardwareMap[device].ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV)); HAL_NVIC_EnableIRQ(i2cHardwareMap[device].ev_irq); }
void ws2811LedStripHardwareInit(void) { TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; TIM_OCInitTypeDef TIM_OCInitStructure; DMA_InitTypeDef DMA_InitStructure; uint16_t prescalerValue; dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP)); RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; /* Time base configuration */ TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure); /* PWM1 Mode configuration: Channel1 */ TIM_OCStructInit(&TIM_OCInitStructure); TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_Pulse = 0; TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; TIM_OC1Init(TIM3, &TIM_OCInitStructure); TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable); TIM_CtrlPWMOutputs(TIM3, ENABLE); /* configure DMA */ /* DMA clock enable */ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); /* DMA1 Channel6 Config */ DMA_DeInit(DMA1_Channel6); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR1; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_Init(DMA1_Channel6, &DMA_InitStructure); /* TIM3 CC1 DMA Request enable */ TIM_DMACmd(TIM3, TIM_DMA_CC1, ENABLE); DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE); const hsvColor_t hsv_white = { 0, 255, 255}; ws2811Initialised = true; setStripColor(&hsv_white); ws2811UpdateStrip(); }
void i2cInit(I2CDevice device) { if (device == I2CINVALID) { return; } i2cDevice_t *pDev = &i2cDevice[device]; const i2cHardware_t *hardware = pDev->hardware; if (!hardware) { return; } IO_t scl = pDev->scl; IO_t sda = pDev->sda; IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device)); IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device)); // Enable RCC RCC_ClockCmd(hardware->rcc, ENABLE); i2cUnstick(scl, sda); // Init pins #ifdef STM32F7 IOConfigGPIOAF(scl, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF4_I2C); IOConfigGPIOAF(sda, pDev->pullUp ? IOCFG_I2C_PU : IOCFG_I2C, GPIO_AF4_I2C); #else IOConfigGPIO(scl, IOCFG_AF_OD); IOConfigGPIO(sda, IOCFG_AF_OD); #endif // Init I2C peripheral I2C_HandleTypeDef *pHandle = &pDev->handle; memset(pHandle, 0, sizeof(*pHandle)); pHandle->Instance = pDev->hardware->reg; /// TODO: HAL check if I2C timing is correct if (pDev->overClock) { // 800khz Maximum speed tested on various boards without issues pHandle->Init.Timing = 0x00500D1D; } else { pHandle->Init.Timing = 0x00500C6F; } pHandle->Init.OwnAddress1 = 0x0; pHandle->Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; pHandle->Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; pHandle->Init.OwnAddress2 = 0x0; pHandle->Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; pHandle->Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; HAL_I2C_Init(pHandle); // Enable the Analog I2C Filter HAL_I2CEx_ConfigAnalogFilter(pHandle, I2C_ANALOGFILTER_ENABLE); // Setup interrupt handlers HAL_NVIC_SetPriority(hardware->er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER)); HAL_NVIC_EnableIRQ(hardware->er_irq); HAL_NVIC_SetPriority(hardware->ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV)); HAL_NVIC_EnableIRQ(hardware->ev_irq); }
void adcInit(adcConfig_t *config) { ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; uint8_t i; uint8_t configuredAdcChannels = 0; memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig)); if (config->vbat.enabled) { adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag; } if (config->rssi.enabled) { adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL; } if (config->external1.enabled) { adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL; } if (config->currentMeter.enabled) { adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL; } ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; adcDevice_t adc = adcHardware[device]; bool adcActive = false; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcOperatingConfig[i].tag) continue; adcActive = true; IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0); IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag); adcOperatingConfig[i].dmaIndex = configuredAdcChannels++; adcOperatingConfig[i].sampleTime = ADC_SampleTime_480Cycles; adcOperatingConfig[i].enabled = true; } if (!adcActive) { return; } RCC_ClockCmd(adc.rccADC, ENABLE); dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0); DMA_DeInit(adc.DMAy_Streamx); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; DMA_InitStructure.DMA_Channel = adc.channel; DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)adcValues; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory; DMA_InitStructure.DMA_BufferSize = configuredAdcChannels; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_MemoryInc = configuredAdcChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_Init(adc.DMAy_Streamx, &DMA_InitStructure); DMA_Cmd(adc.DMAy_Streamx, ENABLE); ADC_CommonInitTypeDef ADC_CommonInitStructure; ADC_CommonStructInit(&ADC_CommonInitStructure); ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div8; ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled; ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles; ADC_CommonInit(&ADC_CommonInitStructure); ADC_StructInit(&ADC_InitStructure); ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels; ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcOperatingConfig[i].enabled) { continue; } ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime); } ADC_DMARequestAfterLastTransferCmd(adc.ADCx, ENABLE); ADC_DMACmd(adc.ADCx, ENABLE); ADC_Cmd(adc.ADCx, ENABLE); ADC_SoftwareStartConv(adc.ADCx); }
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output) { motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; motor->timerHardware = timerHardware; TIM_TypeDef *timer = timerHardware->tim; const IO_t motorIO = IOGetByTag(timerHardware->tag); const uint8_t timerIndex = getTimerIndex(timer); IOInit(motorIO, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction); __DMA1_CLK_ENABLE(); RCC_ClockCmd(timerRCC(timer), ENABLE); motor->TimHandle.Instance = timerHardware->tim; motor->TimHandle.Init.Prescaler = (timerClock(timer) / getDshotHz(pwmProtocolType)) - 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; if (HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK) { /* Initialization Error */ return; } motor->timerDmaSource = timerDmaSource(timerHardware->channel); dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource; /* Set the parameters to be configured */ motor->hdma_tim.Init.Channel = timerHardware->dmaChannel; 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.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; motor->hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; /* Set hdma_tim instance */ if (timerHardware->dmaRef == NULL) { /* Initialization Error */ return; } motor->hdma_tim.Instance = timerHardware->dmaRef; /* Link hdma_tim to hdma[x] (channelx) */ __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) { /* Initialization Error */ return; } TIM_OC_InitTypeDef TIM_OCInitStructure; /* PWM1 Mode configuration: Channel1 */ 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; if (HAL_TIM_PWM_ConfigChannel(&motor->TimHandle, &TIM_OCInitStructure, motor->timerHardware->channel) != HAL_OK) { /* Configuration Error */ return; } }
void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType) { TIM_OCInitTypeDef TIM_OCInitStructure; DMA_InitTypeDef DMA_InitStructure; motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; motor->timerHardware = timerHardware; TIM_TypeDef *timer = timerHardware->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, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction); if (configureTimer) { TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); RCC_ClockCmd(timerRCC(timer), ENABLE); TIM_Cmd(timer, DISABLE); uint32_t hz; switch (pwmProtocolType) { case(PWM_TYPE_DSHOT600): hz = MOTOR_DSHOT600_MHZ * 1000000; break; case(PWM_TYPE_DSHOT300): hz = MOTOR_DSHOT300_MHZ * 1000000; break; default: case(PWM_TYPE_DSHOT150): hz = MOTOR_DSHOT150_MHZ * 1000000; } TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((SystemCoreClock / timerClockDivisor(timer) / hz) - 1); TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH; TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; TIM_TimeBaseStructure.TIM_RepetitionCounter = 0; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure); } TIM_OCStructInit(&TIM_OCInitStructure); TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) { TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable; TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset; TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_Low : TIM_OCNPolarity_High; } else { TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set; TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High; } TIM_OCInitStructure.TIM_Pulse = 0; timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure); timerOCPreloadConfig(timer, timerHardware->channel, TIM_OCPreload_Enable); motor->timerDmaSource = timerDmaSource(timerHardware->channel); dmaMotorTimers[timerIndex].timerDmaSources |= motor->timerDmaSource; TIM_CCxCmd(timer, timerHardware->channel, TIM_CCx_Enable); if (configureTimer) { TIM_CtrlPWMOutputs(timer, ENABLE); TIM_ARRPreloadConfig(timer, ENABLE); TIM_Cmd(timer, ENABLE); } DMA_Channel_TypeDef *channel = timerHardware->dmaChannel; if (channel == NULL) { /* trying to use a non valid channel */ return; } dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex)); dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex); DMA_Cmd(channel, DISABLE); DMA_DeInit(channel); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware); DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)motor->dmaBuffer; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_BufferSize = MOTOR_DMA_BUFFER_SIZE; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word; DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_Init(channel, &DMA_InitStructure); DMA_ITConfig(channel, DMA_IT_TC, ENABLE); }
void i2cInit(I2CDevice device) { if (device == I2CINVALID) return; i2cDevice_t *i2c; i2c = &(i2cHardwareMap[device]); NVIC_InitTypeDef nvic; I2C_InitTypeDef i2cInit; IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device)); IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device)); // Enable RCC RCC_ClockCmd(i2c->rcc, ENABLE); I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); i2cUnstick(scl, sda); // Init pins #ifdef STM32F4 IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C); #else IOConfigGPIO(scl, IOCFG_I2C); IOConfigGPIO(sda, IOCFG_I2C); #endif I2C_DeInit(i2c->dev); I2C_StructInit(&i2cInit); I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request i2cInit.I2C_Mode = I2C_Mode_I2C; i2cInit.I2C_DutyCycle = I2C_DutyCycle_2; i2cInit.I2C_OwnAddress1 = 0; i2cInit.I2C_Ack = I2C_Ack_Enable; i2cInit.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; if (i2c->overClock) { i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues } else { i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs } I2C_Cmd(i2c->dev, ENABLE); I2C_Init(i2c->dev, &i2cInit); I2C_StretchClockCmd(i2c->dev, ENABLE); // I2C ER Interrupt nvic.NVIC_IRQChannel = i2c->er_irq; nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER); nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER); nvic.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&nvic); // I2C EV Interrupt nvic.NVIC_IRQChannel = i2c->ev_irq; nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV); nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV); NVIC_Init(&nvic); }
void adcInit(const adcConfig_t *config) { ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; uint8_t adcChannelCount = 0; memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig)); if (config->vbat.enabled) { adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag; } if (config->rssi.enabled) { adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL; } if (config->external1.enabled) { adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL; } if (config->current.enabled) { adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL; } ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; #ifdef ADC24_DMA_REMAP SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_ADC2ADC4, ENABLE); #endif adcDevice_t adc = adcHardware[device]; bool adcActive = false; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcVerifyPin(adcOperatingConfig[i].tag, device)) { continue; } adcActive = true; IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0); IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag); adcOperatingConfig[i].dmaIndex = adcChannelCount++; adcOperatingConfig[i].sampleTime = ADC_SampleTime_601Cycles5; adcOperatingConfig[i].enabled = true; } if (!adcActive) { return; } if ((device == ADCDEV_1) || (device == ADCDEV_2)) { // enable clock for ADC1+2 RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz } else { // enable clock for ADC3+4 RCC_ADCCLKConfig(RCC_ADC34PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz } RCC_ClockCmd(adc.rccADC, ENABLE); dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC, 0); DMA_DeInit(adc.DMAy_Channelx); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_BufferSize = adcChannelCount; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_MemoryInc = adcChannelCount > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure); DMA_Cmd(adc.DMAy_Channelx, ENABLE); // calibrate ADC_VoltageRegulatorCmd(adc.ADCx, ENABLE); delay(10); ADC_SelectCalibrationMode(adc.ADCx, ADC_CalibrationMode_Single); ADC_StartCalibration(adc.ADCx); while (ADC_GetCalibrationStatus(adc.ADCx) != RESET); ADC_VoltageRegulatorCmd(adc.ADCx, DISABLE); ADC_CommonInitTypeDef ADC_CommonInitStructure; ADC_CommonStructInit(&ADC_CommonInitStructure); ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent; ADC_CommonInitStructure.ADC_Clock = ADC_Clock_SynClkModeDiv4; ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_1; ADC_CommonInitStructure.ADC_DMAMode = ADC_DMAMode_Circular; ADC_CommonInitStructure.ADC_TwoSamplingDelay = 0; ADC_CommonInit(adc.ADCx, &ADC_CommonInitStructure); ADC_StructInit(&ADC_InitStructure); ADC_InitStructure.ADC_ContinuousConvMode = ADC_ContinuousConvMode_Enable; ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b; ADC_InitStructure.ADC_ExternalTrigConvEvent = ADC_ExternalTrigConvEvent_0; ADC_InitStructure.ADC_ExternalTrigEventEdge = ADC_ExternalTrigEventEdge_None; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_OverrunMode = ADC_OverrunMode_Disable; ADC_InitStructure.ADC_AutoInjMode = ADC_AutoInjec_Disable; ADC_InitStructure.ADC_NbrOfRegChannel = adcChannelCount; ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcOperatingConfig[i].enabled) { continue; } ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime); } ADC_Cmd(adc.ADCx, ENABLE); while (!ADC_GetFlagStatus(adc.ADCx, ADC_FLAG_RDY)); ADC_DMAConfig(adc.ADCx, ADC_DMAMode_Circular); ADC_DMACmd(adc.ADCx, ENABLE); ADC_StartConversion(adc.ADCx); }
// USART1 - Telemetry (RX/TX by DMA) uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; s = &uartPort1; s->port.vTable = uartVTable; s->port.baudRate = baudRate; s->port.rxBuffer = rx1Buffer; s->port.txBuffer = tx1Buffer; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE; s->USARTx = USART1; #ifdef USE_UART1_RX_DMA dmaInit(DMA1_CH5_HANDLER, OWNER_SERIAL_RX, 1); s->rxDMAChannel = DMA1_Channel5; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; #endif s->txDMAChannel = DMA1_Channel4; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; RCC_ClockCmd(RCC_APB2(USART1), ENABLE); // UART1_TX PA9 // UART1_RX PA10 if (options & SERIAL_BIDIR) { IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, 1); IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, 1); IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP); } if (mode & MODE_RX) { IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL_RX, 1); IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU); } } // DMA TX Interrupt dmaInit(DMA1_CH4_HANDLER, OWNER_SERIAL_TX, 1); dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1); #ifndef USE_UART1_RX_DMA // RX/TX Interrupt NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_Init(&NVIC_InitStructure); #endif return s; }
void i2cInit(I2CDevice device) { i2cDevice_t *i2c; i2c = &(i2cHardwareMap[device]); I2C_TypeDef *I2Cx; I2Cx = i2c->dev; IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); RCC_ClockCmd(i2c->rcc, ENABLE); RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4); IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4); I2C_InitTypeDef i2cInit = { .I2C_Mode = I2C_Mode_I2C, .I2C_AnalogFilter = I2C_AnalogFilter_Enable, .I2C_DigitalFilter = 0x00, .I2C_OwnAddress1 = 0x00, .I2C_Ack = I2C_Ack_Enable, .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, .I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING) }; I2C_Init(I2Cx, &i2cInit); I2C_StretchClockCmd(I2Cx, ENABLE); I2C_Cmd(I2Cx, ENABLE); } uint16_t i2cGetErrorCounter(void) { return i2cErrorCount; } bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) { addr_ <<= 1; I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { if ((i2cTimeout--) == 0) { return i2cTimeoutUserCallback(); } } /* Configure slave address, nbytes, reload, end mode and start or stop generation */ I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write); /* Wait until TXIS flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { if ((i2cTimeout--) == 0) { return i2cTimeoutUserCallback(); } } /* Send Register address */ I2C_SendData(I2Cx, (uint8_t) reg); /* Wait until TCR flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET) { if ((i2cTimeout--) == 0) { return i2cTimeoutUserCallback(); } } /* Configure slave address, nbytes, reload, end mode and start or stop generation */ I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop); /* Wait until TXIS flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) { if ((i2cTimeout--) == 0) { return i2cTimeoutUserCallback(); } } /* Write data to TXDR */ I2C_SendData(I2Cx, data); /* Wait until STOPF flag is set */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) { if ((i2cTimeout--) == 0) { return i2cTimeoutUserCallback(); } } /* Clear STOPF flag */ I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF); return true; }
void adcInit(drv_adc_config_t *init) { #if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN) UNUSED(init); #endif uint8_t configuredAdcChannels = 0; memset(&adcConfig, 0, sizeof(adcConfig)); #ifdef VBAT_ADC_PIN if (init->enableVBat) { adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN); } #endif #ifdef RSSI_ADC_PIN if (init->enableRSSI) { adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); } #endif #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); } #endif #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); } #endif ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; const adcDevice_t adc = adcHardware[device]; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) continue; IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i, 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = configuredAdcChannels++; adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5; adcConfig[i].enabled = true; } RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) RCC_ClockCmd(adc.rccADC, ENABLE); RCC_ClockCmd(adc.rccDMA, ENABLE); DMA_DeInit(adc.DMAy_Channelx); DMA_InitTypeDef DMA_InitStructure; DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&adc.ADCx->DR; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; DMA_InitStructure.DMA_BufferSize = configuredAdcChannels; DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; DMA_InitStructure.DMA_MemoryInc = configuredAdcChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; DMA_Init(adc.DMAy_Channelx, &DMA_InitStructure); DMA_Cmd(adc.DMAy_Channelx, ENABLE); ADC_InitTypeDef ADC_InitStructure; ADC_StructInit(&ADC_InitStructure); ADC_InitStructure.ADC_Mode = ADC_Mode_Independent; ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; ADC_InitStructure.ADC_NbrOfChannel = configuredAdcChannels; ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); } ADC_DMACmd(adc.ADCx, ENABLE); ADC_Cmd(adc.ADCx, ENABLE); ADC_ResetCalibration(adc.ADCx); while (ADC_GetResetCalibrationStatus(adc.ADCx)); ADC_StartCalibration(adc.ADCx); while (ADC_GetCalibrationStatus(adc.ADCx)); ADC_SoftwareStartConvCmd(adc.ADCx, ENABLE); }
void spiInitDevice(SPIDevice device) { SPI_InitTypeDef spiInit; spiDevice_t *spi = &(spiHardwareMap[device]); #ifdef SDCARD_SPI_INSTANCE if (spi->dev == SDCARD_SPI_INSTANCE) spi->sdcard = true; #endif // Enable SPI clock RCC_ClockCmd(spi->rcc, ENABLE); RCC_ResetCmd(spi->rcc, ENABLE); IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1); IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); #if defined(STM32F3) || defined(STM32F4) IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); if (spi->nss) IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af); #endif #if defined(STM32F10X) IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG); IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG); IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG); if (spi->nss) IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); #endif // Init SPI hardware SPI_I2S_DeInit(spi->dev); spiInit.SPI_Mode = SPI_Mode_Master; spiInit.SPI_Direction = SPI_Direction_2Lines_FullDuplex; spiInit.SPI_DataSize = SPI_DataSize_8b; spiInit.SPI_NSS = SPI_NSS_Soft; spiInit.SPI_FirstBit = SPI_FirstBit_MSB; spiInit.SPI_CRCPolynomial = 7; spiInit.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; if (spi->sdcard) { spiInit.SPI_CPOL = SPI_CPOL_Low; spiInit.SPI_CPHA = SPI_CPHA_1Edge; } else { spiInit.SPI_CPOL = SPI_CPOL_High; spiInit.SPI_CPHA = SPI_CPHA_2Edge; } #ifdef STM32F303xC // Configure for 8-bit reads. SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF); #endif SPI_Init(spi->dev, &spiInit); SPI_Cmd(spi->dev, ENABLE); if (spi->nss) IOHi(IOGetByTag(spi->nss)); }
void adcInit(const adcConfig_t *config) { uint8_t i; uint8_t configuredAdcChannels = 0; memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig)); if (config->vbat.enabled) { adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag; } if (config->rssi.enabled) { adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL; } if (config->external1.enabled) { adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL; } if (config->current.enabled) { adcOperatingConfig[ADC_CURRENT].tag = config->current.ioTag; //CURRENT_METER_ADC_CHANNEL; } ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; adcDevice_t adc = adcHardware[device]; bool adcActive = false; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcVerifyPin(adcOperatingConfig[i].tag, device)) { continue; } adcActive = true; IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0); IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_NOPULL)); adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag); adcOperatingConfig[i].dmaIndex = configuredAdcChannels++; adcOperatingConfig[i].sampleTime = ADC_SAMPLETIME_480CYCLES; adcOperatingConfig[i].enabled = true; } if (!adcActive) { return; } RCC_ClockCmd(adc.rccADC, ENABLE); dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0); adc.ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8; adc.ADCHandle.Init.ContinuousConvMode = ENABLE; adc.ADCHandle.Init.Resolution = ADC_RESOLUTION_12B; adc.ADCHandle.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T1_CC1; adc.ADCHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; adc.ADCHandle.Init.DataAlign = ADC_DATAALIGN_RIGHT; adc.ADCHandle.Init.NbrOfConversion = configuredAdcChannels; adc.ADCHandle.Init.ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group adc.ADCHandle.Init.DiscontinuousConvMode = DISABLE; adc.ADCHandle.Init.NbrOfDiscConversion = 0; adc.ADCHandle.Init.DMAContinuousRequests = ENABLE; adc.ADCHandle.Init.EOCSelection = DISABLE; adc.ADCHandle.Instance = adc.ADCx; /*##-1- Configure the ADC peripheral #######################################*/ if (HAL_ADC_Init(&adc.ADCHandle) != HAL_OK) { /* Initialization Error */ } adc.DmaHandle.Init.Channel = adc.channel; adc.DmaHandle.Init.Direction = DMA_PERIPH_TO_MEMORY; adc.DmaHandle.Init.PeriphInc = DMA_PINC_DISABLE; adc.DmaHandle.Init.MemInc = configuredAdcChannels > 1 ? DMA_MINC_ENABLE : DMA_MINC_DISABLE; adc.DmaHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; adc.DmaHandle.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; adc.DmaHandle.Init.Mode = DMA_CIRCULAR; adc.DmaHandle.Init.Priority = DMA_PRIORITY_HIGH; adc.DmaHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; adc.DmaHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; adc.DmaHandle.Init.MemBurst = DMA_MBURST_SINGLE; adc.DmaHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; adc.DmaHandle.Instance = adc.DMAy_Streamx; /*##-2- Initialize the DMA stream ##########################################*/ if (HAL_DMA_Init(&adc.DmaHandle) != HAL_OK) { /* Initialization Error */ } __HAL_LINKDMA(&adc.ADCHandle, DMA_Handle, adc.DmaHandle); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcOperatingConfig[i].enabled) { continue; } ADC_ChannelConfTypeDef sConfig; sConfig.Channel = adcOperatingConfig[i].adcChannel; sConfig.Rank = rank++; sConfig.SamplingTime = adcOperatingConfig[i].sampleTime; sConfig.Offset = 0; /*##-3- Configure ADC regular channel ######################################*/ if (HAL_ADC_ConfigChannel(&adc.ADCHandle, &sConfig) != HAL_OK) { /* Channel Configuration Error */ } } //HAL_CLEANINVALIDATECACHE((uint32_t*)&adcValues, configuredAdcChannels); /*##-4- Start the conversion process #######################################*/ if (HAL_ADC_Start_DMA(&adc.ADCHandle, (uint32_t*)&adcValues, configuredAdcChannels) != HAL_OK) { /* Start Conversation Error */ } }