APM:Libraries
adc.h
Go to the documentation of this file.
1 
7 #ifndef _ADC_H_
8 #define _ADC_H_
9 
10 #include "stm32.h"
11 #include "hal_types.h"
12 
14 typedef struct adc_dev {
15  ADC_TypeDef *adcx;
16 } adc_dev;
17 
18 #ifdef __cplusplus
19 extern "C"{
20 #endif
21 
22 extern const adc_dev* const _ADC1;
23 extern const adc_dev* const _ADC2;
24 extern const adc_dev* const _ADC3;
25 
26 extern const adc_dev _adc1;
27 extern const adc_dev _adc2;
28 extern const adc_dev _adc3;
29 
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)
49 
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)
53 
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)
62 
63 #define SMPR_SMP_SET ((uint32_t)0x00000007)
64 #define SQR_SQ_SET ((uint32_t)0x0000001F)
65 #define SQR1_L_RESET ((uint32_t)0xFE0FFFFF)
66 
67 
68 void adc_init(const adc_dev *dev);
69 //void adc_set_extsel(const adc_dev *dev, adc_extsel_event event);
70 void adc_foreach(void (*fn)(const adc_dev*));
71 //void adc_set_sample_rate(const adc_dev *dev, adc_smp_rate smp_rate);
72 
73 uint16_t adc_read(const adc_dev *dev, uint8_t channel);
74 uint16_t vref_read(void);
75 uint16_t temp_read(void);
76 
86 static inline void adc_set_reg_seqlen(const adc_dev *dev, uint8_t length) {
87  /* ADC L Mask */
88 
89  uint32_t tmpreg1 = 0;
90  uint8_t tmpreg2 = 0;
91 
92  /* Get the ADCx SQR1 value */
93  tmpreg1 = dev->adcx->SQR1;
94  /* Clear L bits */
95  tmpreg1 &= SQR1_L_RESET;
96  /* Configure ADCx: regular channel sequence length */
97  /* Set L bits according to ADC_NbrOfConversion value */
98  tmpreg2 |= (uint8_t)(length - (uint8_t)1);
99  tmpreg1 |= ((uint32_t)tmpreg2 << 20);
100  /* Write to ADCx SQR1 */
101  dev->adcx->SQR1 = tmpreg1;
102 }
103 
104 static inline void adc_channel_config(const adc_dev *dev, uint8_t channel, uint8_t rank, uint8_t sampleTime)
105 {
106  /* if ADC_Channel_10 ... ADC_Channel_18 is selected */
107  if (channel > ADC_Channel_9) {
108  uint32_t tmpreg1 = dev->adcx->SMPR1 & ~(SMPR_SMP_SET << (3 * (channel - 10)));
109  dev->adcx->SMPR1 = tmpreg1 | (uint32_t)sampleTime << (3 * (channel - 10));
110  } else {/* channel include in ADC_Channel_[0..9] */
111  uint32_t tmpreg1 = dev->adcx->SMPR2 & ~(SMPR_SMP_SET << (3 * channel));
112  dev->adcx->SMPR2 = tmpreg1 | (uint32_t)sampleTime << (3 * channel);
113  }
114 
115  if (rank < 7) {
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) { /* For Rank 7 to 12 */
119  uint32_t tmpreg1 = dev->adcx->SQR2 & ~(SQR_SQ_SET << (5 * (rank - 7)));
120  dev->adcx->SQR2 = tmpreg1 | (uint32_t)channel << (5 * (rank - 7));
121  } else { /* For Rank 13 to 16 */
122  uint32_t tmpreg1 = dev->adcx->SQR1 & ~(SQR_SQ_SET << (5 * (rank - 13)));
123  dev->adcx->SQR1 = tmpreg1 | (uint32_t)channel << (5 * (rank - 13));
124  }
125 }
126 
131 static inline void adc_enable(const adc_dev *dev) {
132  /* Enable ADCx */
133  /* Set the ADON bit to wake up the ADC from power down mode */
134  dev->adcx->CR2 |= (uint32_t)ADC_CR2_ADON;
135 }
136 
141 static inline void adc_disable(const adc_dev *dev) {
142  dev->adcx->CR2 &= (uint32_t)(~ADC_CR2_ADON);
143 }
144 
148 static inline void adc_disable_all(void) {
150 }
151 
152 static inline void adc_start_conv(const adc_dev *dev)
153 {
154  /* Enable the selected ADC conversion for regular group */
155  dev->adcx->CR2 |= (uint32_t)ADC_CR2_SWSTART;
156 }
157 
158 static inline void adc_vref_enable(){
159  /* Enable the temperature sensor and Vrefint channel*/
160  ADC->CCR |= (uint32_t)ADC_CCR_TSVREFE;
161 }
162 
163 static inline void adc_vref_disable(){
164  /* Disable the temperature sensor and Vrefint channel*/
165  ADC->CCR &= (uint32_t)(~ADC_CCR_TSVREFE);
166 }
167 
168 
169 #ifdef __cplusplus
170 } // extern "C"
171 #endif
172 
173 #endif
#define ADC_Channel_9
Definition: adc.h:39
uint16_t vref_read(void)
void adc_foreach(void(*fn)(const adc_dev *))
Call a function on all ADC devices.
Definition: adc.c:41
struct adc_dev adc_dev
const adc_dev _adc1
Definition: adc.c:16
#define SMPR_SMP_SET
Definition: adc.h:63
ADC_TypeDef * adcx
Definition: adc.h:15
static void adc_channel_config(const adc_dev *dev, uint8_t channel, uint8_t rank, uint8_t sampleTime)
Definition: adc.h:104
STM32 chip-specific definitions.
const adc_dev _adc3
Definition: adc.c:28
static void adc_enable(const adc_dev *dev)
Enable an adc peripheral.
Definition: adc.h:131
uint16_t adc_read(const adc_dev *dev, uint8_t channel)
static void adc_disable(const adc_dev *dev)
Disable an ADC peripheral.
Definition: adc.h:141
const adc_dev *const _ADC1
Definition: adc.c:20
const adc_dev *const _ADC2
Definition: adc.c:26
static void adc_vref_disable()
Definition: adc.h:163
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define SQR1_L_RESET
Definition: adc.h:65
uint16_t temp_read(void)
static void adc_start_conv(const adc_dev *dev)
Definition: adc.h:152
Definition: adc.h:14
static void adc_disable_all(void)
Disable all ADC peripherals.
Definition: adc.h:148
static void adc_vref_enable()
Definition: adc.h:158
static void adc_set_reg_seqlen(const adc_dev *dev, uint8_t length)
Set the regular channel sequence length.
Definition: adc.h:86
#define SQR_SQ_SET
Definition: adc.h:64
const adc_dev _adc2
Definition: adc.c:22
const adc_dev *const _ADC3
Definition: adc.c:32
void adc_init(const adc_dev *dev)
Initialize an ADC peripheral.
Definition: adc.c:56