void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index) { if (options & SERIAL_BIDIR) { ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP ); IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, index); IOConfigGPIOAF(tx, ioCfg, af); if (!(options & SERIAL_INVERTED)) IOLo(tx); // OpenDrain output should be inactive } else { ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP); if (mode & MODE_TX) { IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); IOConfigGPIOAF(tx, ioCfg, af); } if (mode & MODE_RX) { IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); IOConfigGPIOAF(rx, ioCfg, af); } } }
static void hmc5883lConfigureDataReadyInterruptHandling(magDev_t* mag) { #ifdef USE_MAG_DATA_READY_SIGNAL if (mag->magIntExtiTag == IO_TAG_NONE) { return; } const IO_t magIntIO = IOGetByTag(mag->magIntExtiTag); #ifdef ENSURE_MAG_DATA_READY_IS_HIGH uint8_t status = IORead(magIntIO); if (!status) { return; } #endif #if defined (STM32F7) IOInit(magIntIO, OWNER_COMPASS_EXTI, 0); EXTIHandlerInit(&mag->exti, hmc5883_extiHandler); EXTIConfig(magIntIO, &mag->exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); EXTIEnable(magIntIO, true); #else IOInit(magIntIO, OWNER_COMPASS_EXTI, 0); IOConfigGPIO(magIntIO, IOCFG_IN_FLOATING); EXTIHandlerInit(&mag->exti, hmc5883_extiHandler); EXTIConfig(magIntIO, &mag->exti, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising); EXTIEnable(magIntIO, true); #endif #else UNUSED(mag); #endif }
void adcHardwareInit(drv_adc_config_t *init) { UNUSED(init); int configuredAdcChannels = 0; for (int i = ADC_CHN_1; i < ADC_CHN_COUNT; i++) { if (!adcConfig[i].tag) continue; adcDevice_t * adc = &adcHardware[adcConfig[i].adcDevice]; IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_CH1 + (i - ADC_CHN_1), 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = adc->usedChannelCount++; adcConfig[i].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[i].enabled = true; adc->enabled = true; configuredAdcChannels++; } if (configuredAdcChannels == 0) return; RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz for (int i = 0; i < ADCDEV_COUNT; i++) { if (adcHardware[i].enabled) { adcInstanceInit(i); } } }
void mcoInit(const mcoConfig_t *mcoConfig) { // Only configure MCO2 with PLLI2SCLK as source for now. // Other MCO1 and other sources can easily be added. // For all F4 and F7 varianets, MCO1 is on PA8 and MCO2 is on PC9. if (mcoConfig->enabled[1]) { IO_t io = IOGetByTag(DEFIO_TAG_E(PC9)); IOInit(io, OWNER_MCO, 2); HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_PLLI2SCLK, RCC_MCODIV_4); IOConfigGPIOAF(io, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL), GPIO_AF0_MCO); } }
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); }
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 ws2811LedStripHardwareInit(void) { TimHandle.Instance = WS2811_TIMER; TimHandle.Init.Prescaler = 1; TimHandle.Init.Period = 135; // 800kHz TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; if(HAL_TIM_PWM_Init(&TimHandle) != HAL_OK) { /* Initialization Error */ return; } static DMA_HandleTypeDef hdma_tim; ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), WS2811_TIMER_GPIO_AF); __DMA1_CLK_ENABLE(); /* Set the parameters to be configured */ hdma_tim.Init.Channel = WS2811_DMA_CHANNEL; hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH; hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE; hdma_tim.Init.MemInc = DMA_MINC_ENABLE; hdma_tim.Init.PeriphDataAlignment = DMA_PDATAALIGN_WORD ; hdma_tim.Init.MemDataAlignment = DMA_MDATAALIGN_WORD ; hdma_tim.Init.Mode = DMA_NORMAL; hdma_tim.Init.Priority = DMA_PRIORITY_HIGH; hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE; hdma_tim.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_FULL; hdma_tim.Init.MemBurst = DMA_MBURST_SINGLE; hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE; /* Set hdma_tim instance */ hdma_tim.Instance = WS2811_DMA_STREAM; uint32_t channelAddress = 0; switch (WS2811_TIMER_CHANNEL) { case TIM_CHANNEL_1: timDMASource = TIM_DMA_ID_CC1; channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); break; case TIM_CHANNEL_2: timDMASource = TIM_DMA_ID_CC2; channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); break; case TIM_CHANNEL_3: timDMASource = TIM_DMA_ID_CC3; channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); break; case TIM_CHANNEL_4: timDMASource = TIM_DMA_ID_CC4; channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); break; } /* Link hdma_tim to hdma[x] (channelx) */ __HAL_LINKDMA(&TimHandle, hdma[timDMASource], hdma_tim); dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, timDMASource); /* Initialize TIMx DMA handle */ if(HAL_DMA_Init(TimHandle.hdma[timDMASource]) != HAL_OK) { /* Initialization Error */ return; } TIM_OC_InitTypeDef TIM_OCInitStructure; /* PWM1 Mode configuration: Channel1 */ TIM_OCInitStructure.OCMode = TIM_OCMODE_PWM1; TIM_OCInitStructure.Pulse = 0; TIM_OCInitStructure.OCPolarity = TIM_OCPOLARITY_HIGH; TIM_OCInitStructure.OCIdleState = TIM_OCIDLESTATE_RESET; TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET; TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE; if(HAL_TIM_PWM_ConfigChannel(&TimHandle, &TIM_OCInitStructure, WS2811_TIMER_CHANNEL) != HAL_OK) { /* Configuration Error */ return; } const hsvColor_t hsv_white = { 0, 255, 255}; ws2811Initialised = true; setStripColor(&hsv_white); }
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; } }
void adcInit(drv_adc_config_t *init) { ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; uint8_t i; uint8_t configuredAdcChannels = 0; memset(&adcConfig, 0, sizeof(adcConfig)); #if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN) UNUSED(init); #endif #ifdef VBAT_ADC_PIN if (init->enableVBat) { IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL; adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++; adcConfig[ADC_BATTERY].enabled = true; adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_480Cycles; } #endif #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL; adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++; adcConfig[ADC_EXTERNAL1].enabled = true; adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_480Cycles; } #endif #ifdef RSSI_ADC_PIN if (init->enableRSSI) { IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL; adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++; adcConfig[ADC_RSSI].enabled = true; adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_480Cycles; } #endif #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL; adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++; adcConfig[ADC_CURRENT].enabled = true; adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_480Cycles; } #endif //RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE); RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE); RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE); DMA_DeInit(DMA2_Stream4); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR; DMA_InitStructure.DMA_Channel = DMA_Channel_0; 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(DMA2_Stream4, &DMA_InitStructure); DMA_Cmd(DMA2_Stream4, ENABLE); // calibrate /* ADC_VoltageRegulatorCmd(ADC1, ENABLE); delay(10); ADC_SelectCalibrationMode(ADC1, ADC_CalibrationMode_Single); ADC_StartCalibration(ADC1); while(ADC_GetCalibrationStatus(ADC1) != RESET); ADC_VoltageRegulatorCmd(ADC1, DISABLE); */ 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(ADC1, &ADC_InitStructure); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); } ADC_DMARequestAfterLastTransferCmd(ADC1, ENABLE); ADC_DMACmd(ADC1, ENABLE); ADC_Cmd(ADC1, ENABLE); ADC_SoftwareStartConv(ADC1); }
void adcInit(drv_adc_config_t *init) { ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; uint8_t i; uint8_t adcChannelCount = 0; memset(&adcConfig, 0, sizeof(adcConfig)); #ifdef VBAT_ADC_PIN if (init->enableVBat) { IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL; adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount; adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_BATTERY].enabled = true; adcChannelCount++; } #endif #ifdef RSSI_ADC_PIN if (init->enableRSSI) { IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL; adcConfig[ADC_RSSI].dmaIndex = adcChannelCount; adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_RSSI].enabled = true; adcChannelCount++; } #endif #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL; adcConfig[ADC_CURRENT].dmaIndex = adcChannelCount; adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_CURRENT].enabled = true; adcChannelCount++; } #endif #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC); IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL; adcConfig[ADC_EXTERNAL1].dmaIndex = adcChannelCount; adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_601Cycles5; adcConfig[ADC_EXTERNAL1].enabled = true; adcChannelCount++; } #endif RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz RCC_AHBPeriphClockCmd(ADC_AHB_PERIPHERAL | RCC_AHBPeriph_ADC12, ENABLE); DMA_DeInit(ADC_DMA_CHANNEL); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC_INSTANCE->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_DMA_CHANNEL, &DMA_InitStructure); DMA_Cmd(ADC_DMA_CHANNEL, ENABLE); // calibrate ADC_VoltageRegulatorCmd(ADC_INSTANCE, ENABLE); delay(10); ADC_SelectCalibrationMode(ADC_INSTANCE, ADC_CalibrationMode_Single); ADC_StartCalibration(ADC_INSTANCE); while(ADC_GetCalibrationStatus(ADC_INSTANCE) != RESET); ADC_VoltageRegulatorCmd(ADC_INSTANCE, 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_INSTANCE, &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_INSTANCE, &ADC_InitStructure); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } ADC_RegularChannelConfig(ADC_INSTANCE, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime); } ADC_Cmd(ADC_INSTANCE, ENABLE); while(!ADC_GetFlagStatus(ADC_INSTANCE, ADC_FLAG_RDY)); ADC_DMAConfig(ADC_INSTANCE, ADC_DMAMode_Circular); ADC_DMACmd(ADC_INSTANCE, ENABLE); ADC_StartConversion(ADC_INSTANCE); }
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 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 adcInit(drv_adc_config_t *init) { uint8_t i; 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); //VBAT_ADC_CHANNEL; } #endif #ifdef RSSI_ADC_PIN if (init->enableRSSI) { adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL; } #endif #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL; } #endif #ifdef CURRENT_METER_ADC_PIN if (init->enableCurrentMeter) { adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); //CURRENT_METER_ADC_CHANNEL; } #endif __HAL_RCC_DMA2_CLK_ENABLE(); __HAL_RCC_ADC1_CLK_ENABLE(); AdcHandle_1.Instance = ADC1; AdcHandle_1.Init.ClockPrescaler = ADC_CLOCKPRESCALER_PCLK_DIV8; AdcHandle_1.Init.Resolution = ADC_RESOLUTION_12B; AdcHandle_1.Init.ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; AdcHandle_1.Init.ContinuousConvMode = ENABLE; AdcHandle_1.Init.DiscontinuousConvMode = DISABLE; AdcHandle_1.Init.NbrOfDiscConversion = 0; AdcHandle_1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; /* Conversion start trigged at each external event */ AdcHandle_1.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T1_CC1; AdcHandle_1.Init.DataAlign = ADC_DATAALIGN_RIGHT; AdcHandle_1.Init.NbrOfConversion = configuredAdcChannels; AdcHandle_1.Init.DMAContinuousRequests = ENABLE; AdcHandle_1.Init.EOCSelection = DISABLE; HAL_ADC_Init(&AdcHandle_1); hdma_adc_1.Instance = MCU_ADC1_DMA_STREAM; hdma_adc_1.Init.Channel = MCU_ADC1_DMA_CHANNEL; hdma_adc_1.Init.Direction = DMA_PERIPH_TO_MEMORY; hdma_adc_1.Init.PeriphInc = DMA_PINC_DISABLE; hdma_adc_1.Init.MemInc = configuredAdcChannels > 1 ? DMA_MINC_ENABLE : DMA_MINC_DISABLE;; hdma_adc_1.Init.PeriphDataAlignment = DMA_PDATAALIGN_HALFWORD; hdma_adc_1.Init.MemDataAlignment = DMA_MDATAALIGN_HALFWORD; hdma_adc_1.Init.Mode = DMA_CIRCULAR; hdma_adc_1.Init.Priority = DMA_PRIORITY_HIGH; hdma_adc_1.Init.FIFOMode = DMA_FIFOMODE_DISABLE; hdma_adc_1.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_HALFFULL; hdma_adc_1.Init.MemBurst = DMA_MBURST_SINGLE; hdma_adc_1.Init.PeriphBurst = DMA_PBURST_SINGLE; HAL_DMA_Init(&hdma_adc_1); /* Associate the initialized DMA handle to the ADC handle */ __HAL_LINKDMA(&AdcHandle_1, DMA_Handle, hdma_adc_1); /* NVIC configuration for DMA transfer complete interrupt */ // HAL_NVIC_SetPriority(MCU_ADC1_DMA_STREAM_IRQn, NVIC_PRIORITY_BASE(NVIC_PRIO_ADC1_DMA), NVIC_PRIORITY_SUB(NVIC_PRIO_ADC1_DMA)); // HAL_NVIC_EnableIRQ(MCU_ADC1_DMA_STREAM_IRQn); uint8_t rank = 1; for (i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); ADC_ChannelConfTypeDef sConfig; sConfig.Channel = adcChannelByTag(adcConfig[i].tag); sConfig.Rank = rank++; sConfig.SamplingTime = ADC_SAMPLETIME_480CYCLES; sConfig.Offset = 0; HAL_ADC_ConfigChannel(&AdcHandle_1, &sConfig); } HAL_ADC_Start_DMA(&AdcHandle_1, (uint32_t*)&adcValues, configuredAdcChannels); }
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 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 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 */ } }