mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_AVR: implement changes to AnalogIn
This commit is contained in:
parent
7049934a69
commit
04d7b5ffe4
|
@ -16,6 +16,7 @@ public:
|
|||
|
||||
/* implement AnalogSource virtual api: */
|
||||
float read();
|
||||
void set_pin(uint8_t p);
|
||||
|
||||
/* implementation specific interface: */
|
||||
|
||||
|
@ -37,7 +38,7 @@ private:
|
|||
volatile uint16_t _sum;
|
||||
|
||||
/* _pin designates the ADC input mux for the sample */
|
||||
const uint8_t _pin;
|
||||
uint8_t _pin;
|
||||
/* prescale scales the raw measurments for read()*/
|
||||
const float _prescale;
|
||||
};
|
||||
|
@ -49,10 +50,11 @@ public:
|
|||
AVRAnalogIn();
|
||||
void init(void* ap_hal_scheduler);
|
||||
AP_HAL::AnalogSource* channel(int n);
|
||||
AP_HAL::AnalogSource* channel(int n, float prescale);
|
||||
|
||||
protected:
|
||||
static ADCSource* _find_or_create_channel(int num);
|
||||
static ADCSource* _create_channel(int num);
|
||||
static ADCSource* _find_or_create_channel(int num, float scale);
|
||||
static ADCSource* _create_channel(int num, float scale);
|
||||
static void _register_channel(ADCSource*);
|
||||
static void _timer_event(uint32_t);
|
||||
static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS];
|
||||
|
|
|
@ -16,6 +16,10 @@ float ADCSource::read() {
|
|||
return _prescale * read_average();
|
||||
}
|
||||
|
||||
void ADCSource::set_pin(uint8_t pin) {
|
||||
_pin = pin;
|
||||
}
|
||||
|
||||
/* read_average is called from the normal thread (not an interrupt). */
|
||||
float ADCSource::read_average() {
|
||||
uint16_t sum;
|
||||
|
@ -28,12 +32,16 @@ float ADCSource::read_average() {
|
|||
while( _sum_count == 0 );
|
||||
|
||||
/* Read and clear in a critical section */
|
||||
uint8_t sreg = SREG;
|
||||
cli();
|
||||
|
||||
sum = _sum;
|
||||
sum_count = _sum_count;
|
||||
_sum = 0;
|
||||
_sum_count = 0;
|
||||
sei();
|
||||
|
||||
SREG = sreg;
|
||||
|
||||
float avg = sum / (float) sum_count;
|
||||
return avg;
|
||||
|
||||
|
|
|
@ -29,17 +29,17 @@ void AVRAnalogIn::init(void* machtnichts) {
|
|||
_register_channel(&_vcc);
|
||||
}
|
||||
|
||||
ADCSource* AVRAnalogIn::_find_or_create_channel(int pin) {
|
||||
ADCSource* AVRAnalogIn::_find_or_create_channel(int pin, float scale) {
|
||||
for(int i = 0; i < _num_channels; i++) {
|
||||
if (_channels[i]->_pin == pin) {
|
||||
return _channels[i];
|
||||
}
|
||||
}
|
||||
return _create_channel(pin);
|
||||
return _create_channel(pin, scale);
|
||||
}
|
||||
|
||||
ADCSource* AVRAnalogIn::_create_channel(int chnum) {
|
||||
ADCSource *ch = new ADCSource(chnum);
|
||||
ADCSource* AVRAnalogIn::_create_channel(int chnum, float scale) {
|
||||
ADCSource *ch = new ADCSource(chnum, scale);
|
||||
_register_channel(ch);
|
||||
return ch;
|
||||
}
|
||||
|
@ -55,9 +55,10 @@ void AVRAnalogIn::_register_channel(ADCSource* ch) {
|
|||
_channels[_num_channels] = ch;
|
||||
/* Need to lock to increment _num_channels as it is used
|
||||
* by the interrupt to access _channels */
|
||||
uint8_t sreg = SREG;
|
||||
cli();
|
||||
_num_channels++;
|
||||
sei();
|
||||
SREG = sreg;
|
||||
|
||||
if (_num_channels == 1) {
|
||||
/* After registering the first channel, we can enable the ADC */
|
||||
|
@ -111,10 +112,13 @@ next_channel:
|
|||
|
||||
|
||||
AP_HAL::AnalogSource* AVRAnalogIn::channel(int ch) {
|
||||
return this->channel(ch, 1.0);
|
||||
}
|
||||
AP_HAL::AnalogSource* AVRAnalogIn::channel(int ch, float scale) {
|
||||
if (ch == ANALOG_INPUT_BOARD_VCC) {
|
||||
return &_vcc;
|
||||
} else {
|
||||
return _find_or_create_channel(ch);
|
||||
return _find_or_create_channel(ch, scale);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue