10 #pragma GCC optimize ("O2") 61 while(RCC_GetFlagStatus(RCC_FLAG_HSIRDY) == RESET);
63 if (dev->
adcx == ADC1)
64 RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
65 else if (dev->
adcx == ADC2)
66 RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC2, ENABLE);
68 RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC3, ENABLE);
72 ADC_InitTypeDef ADC_InitStructure;
73 ADC_CommonInitTypeDef ADC_CommonInitStructure;
75 ADC_CommonStructInit(&ADC_CommonInitStructure);
76 ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div4;
77 ADC_CommonInit(&ADC_CommonInitStructure);
80 ADC_StructInit(&ADC_InitStructure);
81 ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
82 ADC_InitStructure.ADC_ScanConvMode = DISABLE;
83 ADC_InitStructure.ADC_ContinuousConvMode = DISABLE;
84 ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
85 ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
86 ADC_InitStructure.ADC_NbrOfConversion = 1;
87 ADC_Init(dev->
adcx, &ADC_InitStructure);
110 ADC_SoftwareStartConv(dev->
adcx);
113 while (ADC_GetFlagStatus(dev->
adcx, ADC_FLAG_EOC) == RESET);
116 return ADC_GetConversionValue(dev->
adcx);
122 uint16_t res, T_StartupTimeDelay;
124 ADC_TempSensorVrefintCmd(ENABLE);
126 T_StartupTimeDelay = 1024;
127 while (T_StartupTimeDelay--);
136 ADC_SoftwareStartConv(ADC1);
139 while( ADC_GetFlagStatus(ADC1, ADC_FLAG_EOC) == 0 );
141 res += ADC_GetConversionValue(ADC1);
145 ADC_TempSensorVrefintCmd(DISABLE);
153 uint16_t res, T_StartupTimeDelay;
156 ADC_TempSensorVrefintCmd(ENABLE);
159 T_StartupTimeDelay = 1024;
160 while (T_StartupTimeDelay--);
170 ADC_SoftwareStartConv(ADC1);
173 while( ADC_GetFlagStatus(ADC1, ADC_FLAG_EOC) == 0 );
175 res += ADC_GetConversionValue(ADC1);
179 ADC_TempSensorVrefintCmd(DISABLE);
const adc_dev const _adc3
const adc_dev *const _ADC2
const adc_dev *const _ADC1
static void adc_channel_config(const adc_dev *dev, uint8_t channel, uint8_t rank, uint8_t sampleTime)
static void adc_enable(const adc_dev *dev)
Enable an adc peripheral.
uint16_t adc_read(const adc_dev *dev, uint8_t channel)
static void adc_disable(const adc_dev *dev)
Disable an ADC peripheral.
Analog-to-Digital Conversion (ADC) header.
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void adc_foreach(void(*fn)(const adc_dev *))
Call a function on all ADC devices.
const adc_dev *const _ADC3
void adc_init(const adc_dev *dev)
Initialize an ADC peripheral.
#define ADC_SampleTime_84Cycles
__IO uint16_t ADC_ConvertedValue
#define ADC_SampleTime_56Cycles
static void adc_set_reg_seqlen(const adc_dev *dev, uint8_t length)
Set the regular channel sequence length.