mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_AVR: fixed analog input with high channel numbers
This commit is contained in:
parent
fae396e64f
commit
5b92c67286
@ -68,6 +68,7 @@ float ADCSource::_read_average() {
|
||||
|
||||
void ADCSource::setup_read() {
|
||||
if (_pin == ANALOG_INPUT_BOARD_VCC) {
|
||||
ADCSRB = (ADCSRB & ~(1 << MUX5));
|
||||
ADMUX = _BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1);
|
||||
} else if (_pin == ANALOG_INPUT_NONE) {
|
||||
/* noop */
|
||||
|
Loading…
Reference in New Issue
Block a user