HAL_AVR: configure analog inputs as INPUT without pullup

not all pins were defaulting to this, which led to some strange
readings on some devices. First noticed by Andi on a LM335 temperature
sensor
This commit is contained in:
Andrew Tridgell 2013-06-01 12:16:51 +10:00
parent 89bbf5844f
commit c82caeeba1
1 changed files with 24 additions and 3 deletions

View File

@ -15,10 +15,12 @@ ADCSource::ADCSource(uint8_t pin) :
_sum_count(0), _sum_count(0),
_sum(0), _sum(0),
_last_average(0), _last_average(0),
_pin(pin), _pin(ANALOG_INPUT_NONE),
_stop_pin(ANALOG_INPUT_NONE), _stop_pin(ANALOG_INPUT_NONE),
_settle_time_ms(0) _settle_time_ms(0)
{} {
set_pin(pin);
}
float ADCSource::read_average() { float ADCSource::read_average() {
if (_pin == ANALOG_INPUT_BOARD_VCC) { if (_pin == ANALOG_INPUT_BOARD_VCC) {
@ -70,7 +72,26 @@ float ADCSource::voltage_average_ratiometric(void)
} }
void ADCSource::set_pin(uint8_t pin) { void ADCSource::set_pin(uint8_t pin) {
_pin = pin; if (pin != _pin) {
// ensure the pin is marked as an INPUT pin
if (pin != ANALOG_INPUT_NONE && pin != ANALOG_INPUT_BOARD_VCC) {
int8_t dpin = hal.gpio->analogPinToDigitalPin(pin);
if (dpin != -1) {
// enable as input without a pull-up. This gives the
// best results for our analog sensors
hal.gpio->pinMode(dpin, GPIO_INPUT);
hal.gpio->write(dpin, 0);
}
}
uint8_t sreg = SREG;
cli();
_sum = 0;
_sum_count = 0;
_last_average = 0;
_latest = 0;
_pin = pin;
SREG = sreg;
}
} }
void ADCSource::set_stop_pin(uint8_t pin) { void ADCSource::set_stop_pin(uint8_t pin) {