30 #define ADC_Channel_0 ((uint8_t)0x00) 31 #define ADC_Channel_1 ((uint8_t)0x01) 32 #define ADC_Channel_2 ((uint8_t)0x02) 33 #define ADC_Channel_3 ((uint8_t)0x03) 34 #define ADC_Channel_4 ((uint8_t)0x04) 35 #define ADC_Channel_5 ((uint8_t)0x05) 36 #define ADC_Channel_6 ((uint8_t)0x06) 37 #define ADC_Channel_7 ((uint8_t)0x07) 38 #define ADC_Channel_8 ((uint8_t)0x08) 39 #define ADC_Channel_9 ((uint8_t)0x09) 40 #define ADC_Channel_10 ((uint8_t)0x0A) 41 #define ADC_Channel_11 ((uint8_t)0x0B) 42 #define ADC_Channel_12 ((uint8_t)0x0C) 43 #define ADC_Channel_13 ((uint8_t)0x0D) 44 #define ADC_Channel_14 ((uint8_t)0x0E) 45 #define ADC_Channel_15 ((uint8_t)0x0F) 46 #define ADC_Channel_16 ((uint8_t)0x10) 47 #define ADC_Channel_17 ((uint8_t)0x11) 48 #define ADC_Channel_18 ((uint8_t)0x12) 50 #define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) 51 #define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17) 52 #define ADC_Channel_Vbat ((uint8_t)ADC_Channel_18) 54 #define ADC_SampleTime_3Cycles ((uint8_t)0x00) 55 #define ADC_SampleTime_15Cycles ((uint8_t)0x01) 56 #define ADC_SampleTime_28Cycles ((uint8_t)0x02) 57 #define ADC_SampleTime_56Cycles ((uint8_t)0x03) 58 #define ADC_SampleTime_84Cycles ((uint8_t)0x04) 59 #define ADC_SampleTime_112Cycles ((uint8_t)0x05) 60 #define ADC_SampleTime_144Cycles ((uint8_t)0x06) 61 #define ADC_SampleTime_480Cycles ((uint8_t)0x07) 63 #define SMPR_SMP_SET ((uint32_t)0x00000007) 64 #define SQR_SQ_SET ((uint32_t)0x0000001F) 65 #define SQR1_L_RESET ((uint32_t)0xFE0FFFFF) 93 tmpreg1 = dev->
adcx->SQR1;
98 tmpreg2 |= (uint8_t)(length - (uint8_t)1);
99 tmpreg1 |= ((uint32_t)tmpreg2 << 20);
101 dev->
adcx->SQR1 = tmpreg1;
108 uint32_t tmpreg1 = dev->
adcx->SMPR1 & ~(
SMPR_SMP_SET << (3 * (channel - 10)));
109 dev->
adcx->SMPR1 = tmpreg1 | (uint32_t)sampleTime << (3 * (channel - 10));
112 dev->
adcx->SMPR2 = tmpreg1 | (uint32_t)sampleTime << (3 * channel);
116 uint32_t tmpreg1 = dev->
adcx->SQR3 & ~(
SQR_SQ_SET << (5 * (rank - 1)));
117 dev->
adcx->SQR3 = tmpreg1 | (uint32_t)channel << (5 * (rank - 1));
118 }
else if (rank < 13) {
119 uint32_t tmpreg1 = dev->
adcx->SQR2 & ~(
SQR_SQ_SET << (5 * (rank - 7)));
120 dev->
adcx->SQR2 = tmpreg1 | (uint32_t)channel << (5 * (rank - 7));
122 uint32_t tmpreg1 = dev->
adcx->SQR1 & ~(
SQR_SQ_SET << (5 * (rank - 13)));
123 dev->
adcx->SQR1 = tmpreg1 | (uint32_t)channel << (5 * (rank - 13));
134 dev->
adcx->CR2 |= (uint32_t)ADC_CR2_ADON;
142 dev->
adcx->CR2 &= (uint32_t)(~ADC_CR2_ADON);
155 dev->
adcx->CR2 |= (uint32_t)ADC_CR2_SWSTART;
160 ADC->CCR |= (uint32_t)ADC_CCR_TSVREFE;
165 ADC->CCR &= (uint32_t)(~ADC_CCR_TSVREFE);
void adc_foreach(void(*fn)(const adc_dev *))
Call a function on all ADC devices.
static void adc_channel_config(const adc_dev *dev, uint8_t channel, uint8_t rank, uint8_t sampleTime)
STM32 chip-specific definitions.
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.
const adc_dev *const _ADC1
const adc_dev *const _ADC2
static void adc_vref_disable()
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static void adc_start_conv(const adc_dev *dev)
static void adc_disable_all(void)
Disable all ADC peripherals.
static void adc_vref_enable()
static void adc_set_reg_seqlen(const adc_dev *dev, uint8_t length)
Set the regular channel sequence length.
const adc_dev *const _ADC3
void adc_init(const adc_dev *dev)
Initialize an ADC peripheral.