2011-12-16 16:18:29 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-11-12 23:14:55 -04:00
|
|
|
|
2012-06-29 08:48:34 -03:00
|
|
|
#include <FastSerial.h>
|
2011-11-12 23:14:55 -04:00
|
|
|
#include "AP_AnalogSource_Arduino.h"
|
|
|
|
|
2012-06-29 08:48:34 -03:00
|
|
|
// increase this if we need more than 5 analog sources
|
|
|
|
#define MAX_PIN_SOURCES 5
|
|
|
|
|
|
|
|
// number of times to read a pin
|
|
|
|
// before considering the value valid.
|
|
|
|
// This ensures the value has settled on
|
|
|
|
// the new source
|
|
|
|
#define PIN_READ_REPEAT 2
|
|
|
|
|
|
|
|
static uint8_t num_pins_watched;
|
|
|
|
static uint8_t next_pin_index;
|
|
|
|
static uint8_t next_pin_count;
|
|
|
|
static volatile struct {
|
2012-08-17 03:08:47 -03:00
|
|
|
uint8_t pin;
|
|
|
|
uint8_t sum_count;
|
2012-06-29 08:48:34 -03:00
|
|
|
uint16_t output;
|
|
|
|
uint16_t sum;
|
|
|
|
} pins[MAX_PIN_SOURCES];
|
|
|
|
|
|
|
|
// ADC conversion timer. This is called at 1kHz by the timer
|
|
|
|
// interrupt
|
|
|
|
// each conversion takes about 125 microseconds
|
|
|
|
static void adc_timer(uint32_t t)
|
|
|
|
{
|
2012-11-06 06:45:40 -04:00
|
|
|
if (pins[next_pin_index].pin == ANALOG_PIN_NONE) {
|
|
|
|
goto next_pin;
|
|
|
|
}
|
|
|
|
|
2012-08-17 03:08:47 -03:00
|
|
|
if (bit_is_set(ADCSRA, ADSC) || num_pins_watched == 0) {
|
2012-06-29 08:48:34 -03:00
|
|
|
// conversion is still running. This should be
|
|
|
|
// very rare, as we are called at 1kHz
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
next_pin_count++;
|
|
|
|
if (next_pin_count != PIN_READ_REPEAT) {
|
|
|
|
// we don't want this value, so start the next conversion
|
|
|
|
// immediately, discarding this value
|
|
|
|
ADCSRA |= _BV(ADSC);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// remember the value we got
|
2012-11-06 06:45:40 -04:00
|
|
|
{
|
|
|
|
uint8_t low = ADCL;
|
|
|
|
uint8_t high = ADCH;
|
|
|
|
pins[next_pin_index].output = low | (high<<8);
|
|
|
|
}
|
2012-06-29 08:48:34 -03:00
|
|
|
pins[next_pin_index].sum += pins[next_pin_index].output;
|
|
|
|
if (pins[next_pin_index].sum_count >= 63) {
|
|
|
|
// we risk overflowing the 16 bit sum
|
|
|
|
pins[next_pin_index].sum >>= 1;
|
|
|
|
pins[next_pin_index].sum_count = 32;
|
|
|
|
} else {
|
|
|
|
pins[next_pin_index].sum_count++;
|
|
|
|
}
|
|
|
|
|
2012-11-06 06:45:40 -04:00
|
|
|
next_pin:
|
2012-06-29 08:48:34 -03:00
|
|
|
next_pin_count = 0;
|
|
|
|
if (num_pins_watched != 0) {
|
|
|
|
next_pin_index = (next_pin_index+1) % num_pins_watched;
|
|
|
|
}
|
|
|
|
uint8_t pin = pins[next_pin_index].pin;
|
|
|
|
|
2012-11-06 06:45:40 -04:00
|
|
|
if (pin == ANALOG_PIN_NONE) {
|
|
|
|
// setup for returning 0
|
|
|
|
pins[next_pin_index].output = 0;
|
|
|
|
pins[next_pin_index].sum = 0;
|
|
|
|
pins[next_pin_index].sum_count = 1;
|
|
|
|
} else if (pin == ANALOG_PIN_VCC) {
|
2012-06-29 08:48:34 -03:00
|
|
|
// we're reading the board voltage
|
|
|
|
ADMUX = _BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1);
|
2012-11-06 06:45:40 -04:00
|
|
|
|
|
|
|
// start the next conversion
|
|
|
|
ADCSRA |= _BV(ADSC);
|
2012-06-29 08:48:34 -03:00
|
|
|
} else {
|
|
|
|
// we're reading an external pin
|
|
|
|
ADCSRB = (ADCSRB & ~(1 << MUX5)) | (((pin >> 3) & 0x01) << MUX5);
|
|
|
|
ADMUX = _BV(REFS0) | (pin & 0x07);
|
|
|
|
|
2012-11-06 06:45:40 -04:00
|
|
|
// start the next conversion
|
|
|
|
ADCSRA |= _BV(ADSC);
|
|
|
|
}
|
2012-06-29 08:48:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// setup the timer process. This must be called before any analog
|
|
|
|
// values are available
|
|
|
|
void AP_AnalogSource_Arduino::init_timer(AP_PeriodicProcess * scheduler)
|
|
|
|
{
|
|
|
|
scheduler->register_process(adc_timer);
|
|
|
|
}
|
|
|
|
|
|
|
|
// read raw 16 bit value
|
|
|
|
uint16_t AP_AnalogSource_Arduino::read_raw(void)
|
|
|
|
{
|
|
|
|
uint16_t ret;
|
2012-11-20 07:30:08 -04:00
|
|
|
uint8_t oldSREG = SREG;
|
2012-06-29 08:48:34 -03:00
|
|
|
cli();
|
|
|
|
ret = pins[_pin_index].output;
|
2012-11-20 07:30:08 -04:00
|
|
|
SREG = oldSREG;
|
2012-06-29 08:48:34 -03:00
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
|
|
|
// scaled read for board Vcc
|
|
|
|
uint16_t AP_AnalogSource_Arduino::read_vcc(void)
|
|
|
|
{
|
2012-07-06 06:56:12 -03:00
|
|
|
uint16_t v = read_raw();
|
|
|
|
if (v == 0) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
return 1126400UL / v;
|
2012-06-29 08:48:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// read the average 16 bit value since the last
|
|
|
|
// time read_average() was called. This gives a very cheap
|
|
|
|
// filtered value, as new values are produced at 500/N Hz
|
|
|
|
// where N is the total number of analog sources
|
2012-08-14 23:33:44 -03:00
|
|
|
float AP_AnalogSource_Arduino::read_average(void)
|
2012-06-29 08:48:34 -03:00
|
|
|
{
|
|
|
|
uint16_t sum;
|
|
|
|
uint8_t sum_count;
|
|
|
|
|
|
|
|
// we don't expect this loop to trigger, unless
|
|
|
|
// you call read_average() very frequently
|
|
|
|
while (pins[_pin_index].sum_count == 0) ;
|
|
|
|
|
2012-11-20 07:30:08 -04:00
|
|
|
uint8_t oldSREG = SREG;
|
2012-06-29 08:48:34 -03:00
|
|
|
cli();
|
|
|
|
sum = pins[_pin_index].sum;
|
|
|
|
sum_count = pins[_pin_index].sum_count;
|
|
|
|
pins[_pin_index].sum = 0;
|
|
|
|
pins[_pin_index].sum_count = 0;
|
2012-11-20 07:30:08 -04:00
|
|
|
SREG = oldSREG;
|
2012-08-14 23:33:44 -03:00
|
|
|
return sum / (float)sum_count;
|
2012-06-29 08:48:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// read with the prescaler. This uses the averaged value since
|
|
|
|
// the last read, which matches that the AP_ADC APM1 library does
|
|
|
|
// for ADC sources
|
2011-12-16 16:18:29 -04:00
|
|
|
float AP_AnalogSource_Arduino::read(void)
|
2011-11-12 23:14:55 -04:00
|
|
|
{
|
2012-06-29 08:48:34 -03:00
|
|
|
return read_average() * _prescale;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2012-10-16 03:20:15 -03:00
|
|
|
// remap pin numbers to physical pin
|
|
|
|
uint8_t AP_AnalogSource_Arduino::_remap_pin(uint8_t pin)
|
2012-06-29 08:48:34 -03:00
|
|
|
{
|
2012-11-06 06:45:40 -04:00
|
|
|
if (pin != ANALOG_PIN_VCC && pin != ANALOG_PIN_NONE) {
|
2012-07-21 06:49:10 -03:00
|
|
|
// allow pin to be a channel (i.e. "A0") or an actual pin
|
2012-07-11 09:19:17 -03:00
|
|
|
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
2012-07-21 06:49:10 -03:00
|
|
|
if (pin >= 54) pin -= 54;
|
2012-07-11 09:19:17 -03:00
|
|
|
#elif defined(__AVR_ATmega32U4__)
|
2012-07-21 06:49:10 -03:00
|
|
|
if (pin >= 18) pin -= 18;
|
2012-07-11 09:19:17 -03:00
|
|
|
#elif defined(__AVR_ATmega1284__)
|
2012-07-21 06:49:10 -03:00
|
|
|
if (pin >= 24) pin -= 24;
|
2012-07-11 09:19:17 -03:00
|
|
|
#else
|
2012-07-21 06:49:10 -03:00
|
|
|
if (pin >= 14) pin -= 14;
|
2012-07-11 09:19:17 -03:00
|
|
|
#endif
|
2012-07-21 06:49:10 -03:00
|
|
|
}
|
2012-10-16 03:20:15 -03:00
|
|
|
return pin;
|
|
|
|
}
|
|
|
|
|
|
|
|
// assign a slot in the pins_watched
|
|
|
|
void AP_AnalogSource_Arduino::_assign_pin_index(uint8_t pin)
|
|
|
|
{
|
|
|
|
// ensure we don't try to read from too many analog pins
|
|
|
|
if (num_pins_watched == MAX_PIN_SOURCES) {
|
|
|
|
while (true) {
|
|
|
|
Serial.printf_P(PSTR("MAX_PIN_SOURCES REACHED\n"));
|
|
|
|
delay(1000);
|
|
|
|
}
|
|
|
|
}
|
2012-07-11 09:19:17 -03:00
|
|
|
|
2012-10-16 03:20:15 -03:00
|
|
|
pin = _remap_pin(pin);
|
2012-06-29 08:48:34 -03:00
|
|
|
_pin_index = num_pins_watched;
|
|
|
|
pins[_pin_index].pin = pin;
|
|
|
|
num_pins_watched++;
|
|
|
|
if (num_pins_watched == 1) {
|
|
|
|
// enable the ADC
|
2012-08-17 03:08:47 -03:00
|
|
|
PRR0 &= ~_BV(PRADC);
|
|
|
|
ADCSRA |= _BV(ADEN);
|
2012-06-29 08:48:34 -03:00
|
|
|
}
|
2011-11-12 23:14:55 -04:00
|
|
|
}
|
2012-10-16 03:20:15 -03:00
|
|
|
|
|
|
|
// change which pin to read
|
|
|
|
void AP_AnalogSource_Arduino::set_pin(uint8_t pin)
|
|
|
|
{
|
|
|
|
pin = _remap_pin(pin);
|
|
|
|
if (pins[_pin_index].pin != pin) {
|
2012-11-20 07:30:08 -04:00
|
|
|
uint8_t oldSREG = SREG;
|
2012-10-16 03:20:15 -03:00
|
|
|
cli();
|
|
|
|
pins[_pin_index].pin = pin;
|
|
|
|
pins[_pin_index].sum = 0;
|
|
|
|
pins[_pin_index].sum_count = 0;
|
2012-11-20 07:30:08 -04:00
|
|
|
SREG = oldSREG;
|
2012-10-16 03:20:15 -03:00
|
|
|
}
|
|
|
|
}
|