mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_HAL_AVR: AnalogIn implemented
This commit is contained in:
parent
279a755ab3
commit
72f8667d9c
@ -29,7 +29,8 @@ static AVRUARTDriverInstance(avrUart3Driver, 3);
|
||||
|
||||
static AVRI2CDriver avrI2CDriver;
|
||||
static ArduinoSPIDriver arduinoSPIDriver;
|
||||
static ArduinoAnalogIn arduinoAnalogIn;
|
||||
static APM1AnalogIn apm1AnalogIn;
|
||||
static APM2AnalogIn apm2AnalogIn;
|
||||
static AVREEPROMStorage avrEEPROMStorage;
|
||||
static APM1Dataflash apm1Dataflash;
|
||||
static APM2Dataflash apm2Dataflash;
|
||||
@ -47,7 +48,7 @@ const HAL_AVR AP_HAL_AVR_APM1(
|
||||
(UARTDriver*) &avrUart3Driver,
|
||||
&avrI2CDriver,
|
||||
&arduinoSPIDriver,
|
||||
&arduinoAnalogIn,
|
||||
&apm1AnalogIn,
|
||||
&avrEEPROMStorage,
|
||||
&apm1Dataflash,
|
||||
(BetterStream*) &avrUart0Driver,
|
||||
@ -63,7 +64,7 @@ const HAL_AVR AP_HAL_AVR_APM2(
|
||||
(UARTDriver*) &avrUart3Driver,
|
||||
&avrI2CDriver,
|
||||
&arduinoSPIDriver,
|
||||
&arduinoAnalogIn,
|
||||
&apm2AnalogIn,
|
||||
&avrEEPROMStorage,
|
||||
&apm2Dataflash,
|
||||
(BetterStream *) &avrUart0Driver,
|
||||
|
@ -8,7 +8,10 @@ namespace AP_HAL_AVR {
|
||||
class AVRUARTDriver;
|
||||
class AVRI2CDriver;
|
||||
class ArduinoSPIDriver;
|
||||
class ArduinoAnalogIn;
|
||||
class ADCSource;
|
||||
class AVRAnalogIn;
|
||||
class APM1AnalogIn;
|
||||
class APM2AnalogIn;
|
||||
class AVREEPROMStorage;
|
||||
class CommonDataflash;
|
||||
class APM1Dataflash;
|
||||
|
@ -5,13 +5,82 @@
|
||||
#include <AP_HAL.h>
|
||||
#include "AP_HAL_AVR_Namespace.h"
|
||||
|
||||
class AP_HAL_AVR::ArduinoAnalogIn : public AP_HAL::AnalogIn {
|
||||
#define AVR_ANALOG_PIN_VCC 255
|
||||
#define AVR_INPUT_MAX_CHANNELS 6
|
||||
|
||||
class AP_HAL_AVR::ADCSource : public AP_HAL::AnalogSource {
|
||||
public:
|
||||
ArduinoAnalogIn() : _init(0) {}
|
||||
void init(int machtnicht) { _init = 1; }
|
||||
/* pin designates the ADC input number, or when == AVR_ANALOG_PIN_VCC,
|
||||
* board vcc */
|
||||
ADCSource(uint8_t pin, float prescale = 1.0);
|
||||
|
||||
/* implement AnalogSource virtual api: */
|
||||
float read();
|
||||
|
||||
/* implementation specific interface: */
|
||||
|
||||
/* new_sample(): called with value of ADC measurments, from interrput */
|
||||
void new_sample(uint16_t);
|
||||
|
||||
/* setup_read(): called to setup ADC registers for next measurment,
|
||||
* from interrupt */
|
||||
void setup_read();
|
||||
|
||||
/* read_average: called to calculate and clear the internal average.
|
||||
* implements read(). */
|
||||
float read_average();
|
||||
private:
|
||||
int _init;
|
||||
/* _sum_count and _sum are used from both an interrupt and normal thread */
|
||||
volatile uint8_t _sum_count;
|
||||
volatile uint16_t _sum;
|
||||
|
||||
/* _pin designates the ADC input mux for the sample */
|
||||
const uint8_t _pin;
|
||||
/* prescale scales the raw measurments for read()*/
|
||||
const float _prescale;
|
||||
};
|
||||
|
||||
|
||||
/* AVRAnalogIn : a concrete class providing the implementations of the
|
||||
* timer event */
|
||||
class AP_HAL_AVR::AVRAnalogIn {
|
||||
public:
|
||||
AVRAnalogIn();
|
||||
protected:
|
||||
static void _register_channel(ADCSource*);
|
||||
static void _timer_event(uint32_t);
|
||||
static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS];
|
||||
static int _num_channels;
|
||||
static int _active_channel;
|
||||
static int _channel_repeat_count;
|
||||
};
|
||||
|
||||
/* APM1AnalogIn and APM2AnalogIn match the implementations in the AVRAnalogIn
|
||||
* class with the AP_HAL::AnalogIn's channel interface. */
|
||||
class AP_HAL_AVR::APM1AnalogIn : public AP_HAL::AnalogIn,
|
||||
public AP_HAL_AVR::AVRAnalogIn {
|
||||
public:
|
||||
APM1AnalogIn();
|
||||
void init(void* ap_hal_scheduler);
|
||||
AP_HAL::AnalogSource* channel(int n);
|
||||
private:
|
||||
ADCSource _bat_voltage;
|
||||
ADCSource _bat_current;
|
||||
ADCSource _vdd;
|
||||
};
|
||||
|
||||
class AP_HAL_AVR::APM2AnalogIn : public AP_HAL::AnalogIn,
|
||||
public AP_HAL_AVR::AVRAnalogIn {
|
||||
public:
|
||||
APM2AnalogIn();
|
||||
void init(void* ap_hal_scheduler);
|
||||
AP_HAL::AnalogSource* channel(int n);
|
||||
private:
|
||||
ADCSource _pitot;
|
||||
ADCSource _bat_voltage;
|
||||
ADCSource _bat_current;
|
||||
ADCSource _rssi;
|
||||
ADCSource _vdd;
|
||||
};
|
||||
#endif // __AP_HAL_AVR_ANALOG_IN_H__
|
||||
|
||||
|
63
libraries/AP_HAL_AVR/AnalogIn_ADC.cpp
Normal file
63
libraries/AP_HAL_AVR/AnalogIn_ADC.cpp
Normal file
@ -0,0 +1,63 @@
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include "AnalogIn.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
ADCSource::ADCSource(uint8_t pin, float prescale) :
|
||||
_pin(pin),
|
||||
_sum_count(0),
|
||||
_sum(0),
|
||||
_prescale(prescale)
|
||||
{}
|
||||
|
||||
float ADCSource::read() {
|
||||
return _prescale * read_average();
|
||||
}
|
||||
|
||||
/* read_average is called from the normal thread (not an interrupt). */
|
||||
float ADCSource::read_average() {
|
||||
uint16_t sum;
|
||||
uint8_t sum_count;
|
||||
|
||||
/* Block until there is a new sample. Will only happen if you
|
||||
* call read_average very frequently.
|
||||
* I don't like the idea of blocking like this but we don't
|
||||
* have a way to bubble control upwards at the moment. -pch */
|
||||
while( _sum_count == 0 );
|
||||
|
||||
/* Read and clear the */
|
||||
cli();
|
||||
sum = _sum;
|
||||
sum_count = _sum_count;
|
||||
_sum = 0;
|
||||
_sum_count = 0;
|
||||
sei();
|
||||
float avg = sum / (float) sum_count;
|
||||
return avg;
|
||||
|
||||
}
|
||||
|
||||
void ADCSource::setup_read() {
|
||||
if (_pin == AVR_ANALOG_PIN_VCC) {
|
||||
ADMUX = _BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1);
|
||||
} else {
|
||||
ADCSRB = (ADCSRB & ~(1 << MUX5)) | (((_pin >> 3) & 0x01) << MUX5);
|
||||
ADMUX = _BV(REFS0) | (_pin & 0x07);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* 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. */
|
||||
void ADCSource::new_sample(uint16_t sample) {
|
||||
_sum += sample;
|
||||
if (_sum_count >= 63) {
|
||||
_sum >>= 1;
|
||||
_sum_count = 32;
|
||||
} else {
|
||||
_sum_count++;
|
||||
}
|
||||
}
|
38
libraries/AP_HAL_AVR/AnalogIn_APM1.cpp
Normal file
38
libraries/AP_HAL_AVR/AnalogIn_APM1.cpp
Normal file
@ -0,0 +1,38 @@
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include "AnalogIn.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
APM1AnalogIn::APM1AnalogIn () :
|
||||
_bat_voltage(ADCSource(0)),
|
||||
_bat_current(ADCSource(1)),
|
||||
_vdd(ADCSource(AVR_ANALOG_PIN_VCC)),
|
||||
AVRAnalogIn()
|
||||
{ }
|
||||
|
||||
void APM1AnalogIn::init(void* machtnichts) {
|
||||
/* Register AVRAnalogIn::_timer_event with the scheduler. */
|
||||
hal.scheduler->register_timer_process(_timer_event, 1000, 0);
|
||||
/* Register each private channel with AVRAnalogIn. */
|
||||
_register_channel(&_bat_voltage);
|
||||
_register_channel(&_bat_current);
|
||||
_register_channel(&_vdd);
|
||||
}
|
||||
|
||||
AP_HAL::AnalogSource* APM1AnalogIn::channel(int ch) {
|
||||
switch(ch) {
|
||||
case 0:
|
||||
return &_bat_voltage;
|
||||
break;
|
||||
case 1:
|
||||
return &_bat_current;
|
||||
break;
|
||||
case 2:
|
||||
return &_vdd;
|
||||
break;
|
||||
default:
|
||||
return NULL;
|
||||
}
|
||||
}
|
50
libraries/AP_HAL_AVR/AnalogIn_APM2.cpp
Normal file
50
libraries/AP_HAL_AVR/AnalogIn_APM2.cpp
Normal file
@ -0,0 +1,50 @@
|
||||
|
||||
#include <AP_HAL.h>
|
||||
|
||||
#include "AnalogIn.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
extern const AP_HAL::HAL &hal;
|
||||
|
||||
APM2AnalogIn::APM2AnalogIn () :
|
||||
_pitot(ADCSource(0, 4.0)),
|
||||
_bat_voltage(ADCSource(1)),
|
||||
_bat_current(ADCSource(2)),
|
||||
_rssi(ADCSource(3, 0.25)),
|
||||
_vdd(ADCSource(AVR_ANALOG_PIN_VCC)),
|
||||
AVRAnalogIn()
|
||||
{ }
|
||||
|
||||
void APM2AnalogIn::init(void * machtichts) {
|
||||
/* Register AVRAnalogIn::_timer_event with the scheduler. */
|
||||
hal.scheduler->register_timer_process(_timer_event, 1000, 0);
|
||||
/* Register each private channel with AVRAnalogIn. */
|
||||
_register_channel(&_pitot);
|
||||
_register_channel(&_bat_voltage);
|
||||
_register_channel(&_bat_current);
|
||||
_register_channel(&_rssi);
|
||||
_register_channel(&_vdd);
|
||||
}
|
||||
|
||||
AP_HAL::AnalogSource* APM2AnalogIn::channel(int ch) {
|
||||
switch(ch) {
|
||||
case 0:
|
||||
return &_bat_voltage;
|
||||
break;
|
||||
case 1:
|
||||
return &_bat_current;
|
||||
break;
|
||||
case 2:
|
||||
return &_vdd;
|
||||
break;
|
||||
case 3:
|
||||
return &_pitot;
|
||||
break;
|
||||
case 4:
|
||||
return &_rssi;
|
||||
break;
|
||||
default:
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
81
libraries/AP_HAL_AVR/AnalogIn_Common.cpp
Normal file
81
libraries/AP_HAL_AVR/AnalogIn_Common.cpp
Normal file
@ -0,0 +1,81 @@
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include "AnalogIn.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/* CHANNEL_READ_REPEAT: how many reads on a channel before using the value.
|
||||
* This seems to be determined empirically */
|
||||
#define CHANNEL_READ_REPEAT 2
|
||||
|
||||
/* Static variable instances */
|
||||
ADCSource* AVRAnalogIn::_channels[AVR_INPUT_MAX_CHANNELS] = {NULL};
|
||||
int AVRAnalogIn::_num_channels = 0;
|
||||
int AVRAnalogIn::_active_channel = 0;
|
||||
int AVRAnalogIn::_channel_repeat_count = 0;
|
||||
|
||||
AVRAnalogIn::AVRAnalogIn() {}
|
||||
|
||||
void AVRAnalogIn::_register_channel(ADCSource* ch) {
|
||||
if (_num_channels >= AVR_INPUT_MAX_CHANNELS) {
|
||||
for(;;) {
|
||||
hal.console->print_P(PSTR(
|
||||
"Error: AP_HAL_AVR::AVRAnalogIn out of channels\r\n"));
|
||||
hal.scheduler->delay(1000);
|
||||
}
|
||||
}
|
||||
_channels[_num_channels] = ch;
|
||||
/* Need to lock to increment _num_channels as it is used
|
||||
* by the interrupt to access _channels */
|
||||
cli();
|
||||
_num_channels++;
|
||||
sei();
|
||||
|
||||
if (_num_channels == 1) {
|
||||
/* After registering the first channel, we can enable the ADC */
|
||||
PRR0 &= ~_BV(PRADC);
|
||||
ADCSRA |= _BV(ADEN);
|
||||
}
|
||||
}
|
||||
|
||||
void AVRAnalogIn::_timer_event(uint32_t t) {
|
||||
if (ADCSRA & _BV(ADSC)) {
|
||||
/* ADC Conversion is still running - this should not happen, as we
|
||||
* are called at 1khz. */
|
||||
return;
|
||||
}
|
||||
|
||||
if (_num_channels == 0) {
|
||||
/* No channels are registered - nothing to be done. */
|
||||
return;
|
||||
}
|
||||
|
||||
_channel_repeat_count++;
|
||||
if (_channel_repeat_count < CHANNEL_READ_REPEAT) {
|
||||
/* Start a new conversion, throw away the current conversion */
|
||||
ADCSRA |= _BV(ADSC);
|
||||
return;
|
||||
} else {
|
||||
_channel_repeat_count = 0;
|
||||
}
|
||||
|
||||
/* Read the conversion registers. */
|
||||
uint8_t low = ADCL;
|
||||
uint8_t high = ADCH;
|
||||
uint16_t sample = low | (((uint16_t)high) << 8);
|
||||
/* Give the active channel a new sample */
|
||||
_channels[_active_channel]->new_sample( sample );
|
||||
/* Move to the next channel */
|
||||
_active_channel = (_active_channel + 1) % _num_channels;
|
||||
/* Setup the next channel's conversion */
|
||||
_channels[_active_channel]->setup_read();
|
||||
/* Start conversion */
|
||||
ADCSRA |= _BV(ADSC);
|
||||
}
|
||||
|
||||
|
||||
|
@ -15,5 +15,6 @@ void HAL_AVR::init(void* opts) const {
|
||||
rcin->init((void*)&isr_registry);
|
||||
rcout->init(NULL);
|
||||
spi->init(NULL);
|
||||
analogin->init(NULL);
|
||||
};
|
||||
|
||||
|
@ -20,7 +20,7 @@ public:
|
||||
AP_HAL::UARTDriver* _uart3,
|
||||
AP_HAL::I2CDriver* _i2c,
|
||||
AP_HAL::SPIDriver* _spi,
|
||||
AP_HAL::AnalogIn* _analogIn,
|
||||
AP_HAL::AnalogIn* _analogin,
|
||||
AP_HAL::Storage* _storage,
|
||||
AP_HAL::Dataflash* _dataflash,
|
||||
AP_HAL::BetterStream* _console,
|
||||
@ -29,7 +29,7 @@ public:
|
||||
AP_HAL::RCOutput* _rcout,
|
||||
AP_HAL::Scheduler* _scheduler)
|
||||
: AP_HAL::HAL( _uart0, _uart1, _uart2, _uart3,
|
||||
_i2c, _spi, _analogIn, _storage,
|
||||
_i2c, _spi, _analogin, _storage,
|
||||
_dataflash, _console, _gpio, _rcin,
|
||||
_rcout, _scheduler) {}
|
||||
|
||||
|
35
libraries/AP_HAL_AVR/examples/AnalogIn/AnalogIn.pde
Normal file
35
libraries/AP_HAL_AVR/examples/AnalogIn/AnalogIn.pde
Normal file
@ -0,0 +1,35 @@
|
||||
|
||||
#include <AP_Common.h>
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_HAL_AVR.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
|
||||
AP_HAL::AnalogSource* ch0;
|
||||
AP_HAL::AnalogSource* ch1;
|
||||
AP_HAL::AnalogSource* vdd;
|
||||
|
||||
void setup (void) {
|
||||
hal.uart0->printf_P(PSTR("Starting AP_HAL_AVR::AnalogIn test\r\n"));
|
||||
ch0 = hal.analogin->channel(0);
|
||||
ch1 = hal.analogin->channel(1);
|
||||
vdd = hal.analogin->channel(2);
|
||||
}
|
||||
|
||||
void loop (void) {
|
||||
float meas_ch0 = ch0->read();
|
||||
float meas_ch1 = ch1->read();
|
||||
float meas_vdd = vdd->read();
|
||||
hal.uart0->printf_P(PSTR("read ch0: %f, ch1: %f, vdd: %f\r\n"),
|
||||
meas_ch0, meas_ch1, meas_vdd);
|
||||
hal.scheduler->delay(10);
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
int main (void) {
|
||||
hal.init(NULL);
|
||||
setup();
|
||||
for(;;) loop();
|
||||
return 0;
|
||||
}
|
||||
}
|
0
libraries/AP_HAL_AVR/examples/AnalogIn/Arduino.h
Normal file
0
libraries/AP_HAL_AVR/examples/AnalogIn/Arduino.h
Normal file
1
libraries/AP_HAL_AVR/examples/AnalogIn/Makefile
Normal file
1
libraries/AP_HAL_AVR/examples/AnalogIn/Makefile
Normal file
@ -0,0 +1 @@
|
||||
include ../../../AP_Common/Arduino.mk
|
Loading…
Reference in New Issue
Block a user