mirror of https://github.com/ArduPilot/ardupilot
AP_AnalogSource: fixed reporting of VCC
the VCC pin number should not be converted
This commit is contained in:
parent
55c342c858
commit
175b6d2606
|
@ -142,6 +142,7 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (pin != ANALOG_PIN_VCC) {
|
||||||
// allow pin to be a channel (i.e. "A0") or an actual pin
|
// allow pin to be a channel (i.e. "A0") or an actual pin
|
||||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||||
if (pin >= 54) pin -= 54;
|
if (pin >= 54) pin -= 54;
|
||||||
|
@ -152,6 +153,7 @@ void AP_AnalogSource_Arduino::assign_pin_index(uint8_t pin)
|
||||||
#else
|
#else
|
||||||
if (pin >= 14) pin -= 14;
|
if (pin >= 14) pin -= 14;
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
_pin_index = num_pins_watched;
|
_pin_index = num_pins_watched;
|
||||||
pins[_pin_index].pin = pin;
|
pins[_pin_index].pin = pin;
|
||||||
|
|
Loading…
Reference in New Issue