mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: change adc sampling rate
STm32l4r5 adc sampling rate.
This commit is contained in:
parent
ecbad5b35a
commit
2207f7bb14
|
@ -531,7 +531,7 @@ void AnalogIn::setup_adc(uint8_t index)
|
|||
adcgrpcfg[index].sqr[2] |= chan << (6*(i-9));
|
||||
}
|
||||
#elif defined(STM32F3) || defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
#if defined(STM32G4) || defined(STM32L4)
|
||||
#if defined(STM32G4) || defined(STM32L4) || defined(STM32L4PLUS)
|
||||
adcgrpcfg[index].smpr[chan/10] |= ADC_SMPR_SMP_640P5 << (3*(chan%10));
|
||||
#else
|
||||
adcgrpcfg[index].smpr[chan/10] |= ADC_SMPR_SMP_601P5 << (3*(chan%10));
|
||||
|
|
Loading…
Reference in New Issue