From 13f7bd172366190cb411c50115fab667b340805c Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Thu, 6 Dec 2012 15:58:00 -0800 Subject: [PATCH] AP_HAL_AVR: AnalogIn supports read_average & read_latest --- libraries/AP_HAL_AVR/AnalogIn.h | 10 ++++++---- libraries/AP_HAL_AVR/AnalogIn_ADC.cpp | 23 +++++++++++++++++------ 2 files changed, 23 insertions(+), 10 deletions(-) diff --git a/libraries/AP_HAL_AVR/AnalogIn.h b/libraries/AP_HAL_AVR/AnalogIn.h index 3a08e27674..b2a750d924 100644 --- a/libraries/AP_HAL_AVR/AnalogIn.h +++ b/libraries/AP_HAL_AVR/AnalogIn.h @@ -15,7 +15,8 @@ public: ADCSource(uint8_t pin, float prescale = 1.0); /* implement AnalogSource virtual api: */ - float read(); + float read_average(); + float read_latest(); void set_pin(uint8_t p); /* implementation specific interface: */ @@ -28,14 +29,15 @@ public: void setup_read(); /* read_average: called to calculate and clear the internal average. - * implements read(). */ - float read_average(); + * implements read_average(), unscaled. */ + float _read_average(); int16_t get_pin() { return _pin; }; private: - /* _sum_count and _sum are used from both an interrupt and normal thread */ + /* following three are used from both an interrupt and normal thread */ volatile uint8_t _sum_count; volatile uint16_t _sum; + volatile uint16_t _latest; /* _pin designates the ADC input mux for the sample */ uint8_t _pin; diff --git a/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp b/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp index bc567636b0..1594904d39 100644 --- a/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp +++ b/libraries/AP_HAL_AVR/AnalogIn_ADC.cpp @@ -12,14 +12,24 @@ ADCSource::ADCSource(uint8_t pin, float prescale) : _prescale(prescale) {} -float ADCSource::read() { +float ADCSource::read_average() { if (_pin == ANALOG_INPUT_BOARD_VCC) { - // XXX we really want a version of this which is using the raw voltage - // and a different one for the low passed average vcc - uint16_t v = (uint16_t) read_average(); + uint16_t v = (uint16_t) _read_average(); return 1126400UL / v; } else { - return _prescale * read_average(); + return _prescale * _read_average(); + } +} + +float ADCSource::read_latest() { + uint8_t sreg = SREG; + cli(); + uint16_t latest = _latest; + SREG = sreg; + if (_pin == ANALOG_INPUT_BOARD_VCC) { + return 1126400UL / latest; + } else { + return _prescale * latest; } } @@ -28,7 +38,7 @@ void ADCSource::set_pin(uint8_t pin) { } /* read_average is called from the normal thread (not an interrupt). */ -float ADCSource::read_average() { +float ADCSource::_read_average() { uint16_t sum; uint8_t sum_count; @@ -70,6 +80,7 @@ void ADCSource::setup_read() { * cli/sei to read these variables from outside an interrupt. */ void ADCSource::new_sample(uint16_t sample) { _sum += sample; + _latest = sample; if (_sum_count >= 63) { _sum >>= 1; _sum_count = 32;