Browse Source

AP_HAL_AVR: AnalogIn supports read_average & read_latest

mission-4.1.18
Pat Hickey 12 years ago committed by Andrew Tridgell
parent
commit
13f7bd1723
  1. 10
      libraries/AP_HAL_AVR/AnalogIn.h
  2. 23
      libraries/AP_HAL_AVR/AnalogIn_ADC.cpp

10
libraries/AP_HAL_AVR/AnalogIn.h

@ -15,7 +15,8 @@ public:
ADCSource(uint8_t pin, float prescale = 1.0); ADCSource(uint8_t pin, float prescale = 1.0);
/* implement AnalogSource virtual api: */ /* implement AnalogSource virtual api: */
float read(); float read_average();
float read_latest();
void set_pin(uint8_t p); void set_pin(uint8_t p);
/* implementation specific interface: */ /* implementation specific interface: */
@ -28,14 +29,15 @@ public:
void setup_read(); void setup_read();
/* read_average: called to calculate and clear the internal average. /* read_average: called to calculate and clear the internal average.
* implements read(). */ * implements read_average(), unscaled. */
float read_average(); float _read_average();
int16_t get_pin() { return _pin; }; int16_t get_pin() { return _pin; };
private: 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 uint8_t _sum_count;
volatile uint16_t _sum; volatile uint16_t _sum;
volatile uint16_t _latest;
/* _pin designates the ADC input mux for the sample */ /* _pin designates the ADC input mux for the sample */
uint8_t _pin; uint8_t _pin;

23
libraries/AP_HAL_AVR/AnalogIn_ADC.cpp

@ -12,14 +12,24 @@ ADCSource::ADCSource(uint8_t pin, float prescale) :
_prescale(prescale) _prescale(prescale)
{} {}
float ADCSource::read() { float ADCSource::read_average() {
if (_pin == ANALOG_INPUT_BOARD_VCC) { if (_pin == ANALOG_INPUT_BOARD_VCC) {
// XXX we really want a version of this which is using the raw voltage uint16_t v = (uint16_t) _read_average();
// and a different one for the low passed average vcc
uint16_t v = (uint16_t) read_average();
return 1126400UL / v; return 1126400UL / v;
} else { } 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). */ /* read_average is called from the normal thread (not an interrupt). */
float ADCSource::read_average() { float ADCSource::_read_average() {
uint16_t sum; uint16_t sum;
uint8_t sum_count; uint8_t sum_count;
@ -70,6 +80,7 @@ void ADCSource::setup_read() {
* cli/sei to read these variables from outside an interrupt. */ * cli/sei to read these variables from outside an interrupt. */
void ADCSource::new_sample(uint16_t sample) { void ADCSource::new_sample(uint16_t sample) {
_sum += sample; _sum += sample;
_latest = sample;
if (_sum_count >= 63) { if (_sum_count >= 63) {
_sum >>= 1; _sum >>= 1;
_sum_count = 32; _sum_count = 32;

Loading…
Cancel
Save