Browse Source

HAL_AVR: support set_stop_pin() and set_settle_time() for analogin

useful for dual sonar support
master
Andrew Tridgell 12 years ago
parent
commit
e7a6b12ac1
  1. 18
      libraries/AP_HAL_AVR/AnalogIn.h
  2. 62
      libraries/AP_HAL_AVR/AnalogIn_ADC.cpp
  3. 17
      libraries/AP_HAL_AVR/AnalogIn_Common.cpp

18
libraries/AP_HAL_AVR/AnalogIn.h

@ -19,7 +19,8 @@ public: @@ -19,7 +19,8 @@ public:
float read_latest();
void set_pin(uint8_t p);
float voltage_average();
void set_stop_pin(uint8_t p);
void set_settle_time(uint16_t settle_time_ms);
/* implementation specific interface: */
@ -30,6 +31,12 @@ public: @@ -30,6 +31,12 @@ public:
* from interrupt */
void setup_read();
/* stop_read(): called to stop device measurement */
void stop_read();
/* reading_settled(): called to check if we have read for long enough */
bool reading_settled();
/* read_average: called to calculate and clear the internal average.
* implements read_average(), unscaled. */
float _read_average();
@ -44,6 +51,13 @@ private: @@ -44,6 +51,13 @@ private:
/* _pin designates the ADC input mux for the sample */
uint8_t _pin;
/* _stop_pin designates a digital pin to use for
enabling/disabling the analog device */
uint8_t _stop_pin;
uint16_t _settle_time_ms;
uint32_t _read_start_time_ms;
/* prescale scales the raw measurments for read()*/
const float _prescale;
};
@ -64,7 +78,7 @@ protected: @@ -64,7 +78,7 @@ protected:
static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS];
static int16_t _num_channels;
static int16_t _active_channel;
static int16_t _channel_repeat_count;
static uint16_t _channel_repeat_count;
private:
ADCSource _vcc;

62
libraries/AP_HAL_AVR/AnalogIn_ADC.cpp

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
@ -11,6 +13,7 @@ extern const AP_HAL::HAL& hal; @@ -11,6 +13,7 @@ extern const AP_HAL::HAL& hal;
ADCSource::ADCSource(uint8_t pin, float prescale) :
_pin(pin),
_stop_pin(ANALOG_INPUT_NONE),
_sum_count(0),
_sum(0),
_prescale(prescale)
@ -42,30 +45,39 @@ float ADCSource::read_latest() { @@ -42,30 +45,39 @@ float ADCSource::read_latest() {
*/
float ADCSource::voltage_average(void)
{
float vcc_mV = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC)->read_average();
float v = read_average();
// constrain Vcc reading so that a bad Vcc doesn't throw off
// the reading of other sources too badly
if (vcc_mV < 4000) {
vcc_mV = 4000;
} else if (vcc_mV > 6000) {
vcc_mV = 6000;
}
return v * vcc_mV * 9.765625e-7; // 9.765625e-7 = 1.0/(1024*1000)
float vcc_mV = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC)->read_average();
float v = read_average();
// constrain Vcc reading so that a bad Vcc doesn't throw off
// the reading of other sources too badly
if (vcc_mV < 4000) {
vcc_mV = 4000;
} else if (vcc_mV > 6000) {
vcc_mV = 6000;
}
return v * vcc_mV * 9.765625e-7; // 9.765625e-7 = 1.0/(1024*1000)
}
void ADCSource::set_pin(uint8_t pin) {
_pin = pin;
}
void ADCSource::set_stop_pin(uint8_t pin) {
_stop_pin = pin;
}
void ADCSource::set_settle_time(uint16_t settle_time_ms)
{
_settle_time_ms = settle_time_ms;
}
/* read_average is called from the normal thread (not an interrupt). */
float ADCSource::_read_average() {
uint16_t sum;
uint8_t sum_count;
if (_sum_count == 0) {
// avoid blocking waiting for new samples
return _last_average;
// avoid blocking waiting for new samples
return _last_average;
}
/* Read and clear in a critical section */
@ -86,8 +98,16 @@ float ADCSource::_read_average() { @@ -86,8 +98,16 @@ float ADCSource::_read_average() {
}
void ADCSource::setup_read() {
if (_stop_pin != ANALOG_INPUT_NONE) {
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
hal.gpio->pinMode(digital_pin, GPIO_OUTPUT);
hal.gpio->write(digital_pin, 1);
}
if (_settle_time_ms != 0) {
_read_start_time_ms = hal.scheduler->millis();
}
if (_pin == ANALOG_INPUT_BOARD_VCC) {
ADCSRB = (ADCSRB & ~(1 << MUX5));
ADCSRB = (ADCSRB & ~(1 << MUX5));
ADMUX = _BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1);
} else if (_pin == ANALOG_INPUT_NONE) {
/* noop */
@ -97,6 +117,22 @@ void ADCSource::setup_read() { @@ -97,6 +117,22 @@ void ADCSource::setup_read() {
}
}
void ADCSource::stop_read() {
if (_stop_pin != ANALOG_INPUT_NONE) {
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
hal.gpio->pinMode(digital_pin, GPIO_OUTPUT);
hal.gpio->write(digital_pin, 0);
}
}
bool ADCSource::reading_settled()
{
if (_settle_time_ms != 0 && (hal.scheduler->millis() - _read_start_time_ms) < _settle_time_ms) {
return false;
}
return true;
}
/* new_sample is called from an interrupt. It always has access to
* _sum and _sum_count. Lock out the interrupts briefly with
* cli/sei to read these variables from outside an interrupt. */

17
libraries/AP_HAL_AVR/AnalogIn_Common.cpp

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include <AP_HAL.h>
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
@ -18,7 +20,7 @@ extern const AP_HAL::HAL& hal; @@ -18,7 +20,7 @@ extern const AP_HAL::HAL& hal;
ADCSource* AVRAnalogIn::_channels[AVR_INPUT_MAX_CHANNELS] = {NULL};
int16_t AVRAnalogIn::_num_channels = 0;
int16_t AVRAnalogIn::_active_channel = 0;
int16_t AVRAnalogIn::_channel_repeat_count = 0;
uint16_t AVRAnalogIn::_channel_repeat_count = 0;
AVRAnalogIn::AVRAnalogIn() :
_vcc(ADCSource(ANALOG_INPUT_BOARD_VCC))
@ -60,8 +62,8 @@ void AVRAnalogIn::_register_channel(ADCSource* ch) { @@ -60,8 +62,8 @@ void AVRAnalogIn::_register_channel(ADCSource* ch) {
}
}
void AVRAnalogIn::_timer_event(uint32_t t) {
void AVRAnalogIn::_timer_event(uint32_t t)
{
if (_channels[_active_channel]->_pin == ANALOG_INPUT_NONE) {
_channels[_active_channel]->new_sample(0);
goto next_channel;
@ -79,14 +81,15 @@ void AVRAnalogIn::_timer_event(uint32_t t) { @@ -79,14 +81,15 @@ void AVRAnalogIn::_timer_event(uint32_t t) {
}
_channel_repeat_count++;
if (_channel_repeat_count < CHANNEL_READ_REPEAT) {
if (_channel_repeat_count < CHANNEL_READ_REPEAT ||
!_channels[_active_channel]->reading_settled()) {
/* Start a new conversion, throw away the current conversion */
ADCSRA |= _BV(ADSC);
return;
} else {
_channel_repeat_count = 0;
}
_channel_repeat_count = 0;
/* Read the conversion registers. */
{
uint8_t low = ADCL;
@ -96,6 +99,8 @@ void AVRAnalogIn::_timer_event(uint32_t t) { @@ -96,6 +99,8 @@ void AVRAnalogIn::_timer_event(uint32_t t) {
_channels[_active_channel]->new_sample( sample );
}
next_channel:
/* stop the previous channel, if a stop pin is defined */
_channels[_active_channel]->stop_read();
/* Move to the next channel */
_active_channel = (_active_channel + 1) % _num_channels;
/* Setup the next channel's conversion */

Loading…
Cancel
Save