AP_HAL_ChibiOS: Add ADC1 support to STM32F3

This is useful for AP_Periph battery monitoring
This commit is contained in:
Tom Pittenger 2021-02-04 15:22:41 -08:00 committed by Tom Pittenger
parent 09f04e8a5a
commit d1e6b0befb
1 changed files with 11 additions and 1 deletions

View File

@ -209,7 +209,7 @@ void AnalogIn::init()
adcgrpcfg.circular = true;
adcgrpcfg.num_channels = ADC_GRP1_NUM_CHANNELS;
adcgrpcfg.end_cb = adccallback;
#if defined(STM32H7)
#if defined(STM32H7) || defined(STM32F3)
// use 12 bits resolution to keep scaling factors the same as other boards.
// todo: enable oversampling in cfgr2 ?
adcgrpcfg.cfgr = ADC_CFGR_CONT | ADC_CFGR_RES_12BITS;
@ -231,6 +231,16 @@ void AnalogIn::init()
} else {
adcgrpcfg.sqr[2] |= chan << (6*(i-9));
}
#elif defined(STM32F3)
adcgrpcfg.smpr[chan/10] |= ADC_SMPR_SMP_601P5 << (3*(chan%10));
// setup channel sequence
if (i < 4) {
adcgrpcfg.sqr[0] |= chan << (6*(i+1));
} else if (i < 9) {
adcgrpcfg.sqr[1] |= chan << (6*(i-4));
} else {
adcgrpcfg.sqr[2] |= chan << (6*(i-9));
}
#else
if (chan < 10) {
adcgrpcfg.smpr2 |= ADC_SAMPLE_480 << (3*chan);