mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added voltage_average() interface to AnalogIn
returns voltage in Volts, using averaged reading over samples. Where possible this should be auto-scaled against a known reference voltage
This commit is contained in:
parent
0d5e731a65
commit
b1c27407a2
|
@ -9,6 +9,10 @@ public:
|
|||
virtual float read_average() = 0;
|
||||
virtual float read_latest() = 0;
|
||||
virtual void set_pin(uint8_t p) = 0;
|
||||
|
||||
// return a voltage from 0.0 to 5.0V, scaled
|
||||
// against a reference voltage
|
||||
virtual float voltage_average() = 0;
|
||||
};
|
||||
|
||||
class AP_HAL::AnalogIn {
|
||||
|
|
|
@ -18,6 +18,8 @@ public:
|
|||
float read_average();
|
||||
float read_latest();
|
||||
void set_pin(uint8_t p);
|
||||
float voltage_average();
|
||||
|
||||
|
||||
/* implementation specific interface: */
|
||||
|
||||
|
@ -38,6 +40,7 @@ private:
|
|||
volatile uint8_t _sum_count;
|
||||
volatile uint16_t _sum;
|
||||
volatile uint16_t _latest;
|
||||
float _last_average;
|
||||
|
||||
/* _pin designates the ADC input mux for the sample */
|
||||
uint8_t _pin;
|
||||
|
|
|
@ -7,6 +7,8 @@
|
|||
#include "AnalogIn.h"
|
||||
using namespace AP_HAL_AVR;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
ADCSource::ADCSource(uint8_t pin, float prescale) :
|
||||
_pin(pin),
|
||||
_sum_count(0),
|
||||
|
@ -35,6 +37,16 @@ float ADCSource::read_latest() {
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
return voltage from 0.0 to 5.0V, scaled to Vcc
|
||||
*/
|
||||
float ADCSource::voltage_average(void)
|
||||
{
|
||||
float vcc_mV = hal.analogin->channel(ANALOG_INPUT_BOARD_VCC)->read_average();
|
||||
float v = read_average();
|
||||
return v * vcc_mV * 9.765625e-7; // 9.765625e-7 = 1.0/(1024*1000)
|
||||
}
|
||||
|
||||
void ADCSource::set_pin(uint8_t pin) {
|
||||
_pin = pin;
|
||||
}
|
||||
|
@ -44,11 +56,10 @@ 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 );
|
||||
if (_sum_count == 0) {
|
||||
// avoid blocking waiting for new samples
|
||||
return _last_average;
|
||||
}
|
||||
|
||||
/* Read and clear in a critical section */
|
||||
uint8_t sreg = SREG;
|
||||
|
@ -62,8 +73,9 @@ float ADCSource::_read_average() {
|
|||
SREG = sreg;
|
||||
|
||||
float avg = sum / (float) sum_count;
|
||||
return avg;
|
||||
|
||||
_last_average = avg;
|
||||
return avg;
|
||||
}
|
||||
|
||||
void ADCSource::setup_read() {
|
||||
|
|
|
@ -21,6 +21,10 @@ float ADCSource::read_average() {
|
|||
return read_latest();
|
||||
}
|
||||
|
||||
float ADCSource::voltage_average() {
|
||||
return (5.0/1024.0) * read_average();
|
||||
}
|
||||
|
||||
float ADCSource::read_latest() {
|
||||
switch (_pin) {
|
||||
case ANALOG_INPUT_BOARD_VCC:
|
||||
|
|
|
@ -18,6 +18,7 @@ public:
|
|||
float read_average();
|
||||
float read_latest();
|
||||
void set_pin(uint8_t p);
|
||||
float voltage_average();
|
||||
|
||||
private:
|
||||
/* prescale scales the raw measurments for read()*/
|
||||
|
|
|
@ -11,6 +11,10 @@ float EmptyAnalogSource::read_average() {
|
|||
return _v;
|
||||
}
|
||||
|
||||
float EmptyAnalogSource::voltage_average() {
|
||||
return 5.0 * _v / 1024.0;
|
||||
}
|
||||
|
||||
float EmptyAnalogSource::read_latest() {
|
||||
return _v;
|
||||
}
|
||||
|
|
|
@ -10,6 +10,7 @@ public:
|
|||
float read_average();
|
||||
float read_latest();
|
||||
void set_pin(uint8_t p);
|
||||
float voltage_average();
|
||||
private:
|
||||
float _v;
|
||||
};
|
||||
|
|
|
@ -55,6 +55,14 @@ float PX4AnalogSource::read_latest()
|
|||
return _latest_value;
|
||||
}
|
||||
|
||||
/*
|
||||
return voltage in Volts
|
||||
*/
|
||||
float PX4AnalogSource::voltage_average()
|
||||
{
|
||||
return (5.0f/1024.0f) * read_average();
|
||||
}
|
||||
|
||||
void PX4AnalogSource::set_pin(uint8_t pin)
|
||||
{
|
||||
_pin = pin;
|
||||
|
|
|
@ -15,6 +15,8 @@ public:
|
|||
float read_average();
|
||||
float read_latest();
|
||||
void set_pin(uint8_t p);
|
||||
float voltage_average();
|
||||
|
||||
private:
|
||||
// what pin it is attached to
|
||||
int16_t _pin;
|
||||
|
|
|
@ -11,6 +11,11 @@ float SMACCMAnalogSource::read_average() {
|
|||
return _v;
|
||||
}
|
||||
|
||||
float SMACCMAnalogSource::voltage_average() {
|
||||
// this assumes 5.0V scaling and 1024 range
|
||||
return (5.0/1024.0) * read_average();
|
||||
}
|
||||
|
||||
float SMACCMAnalogSource::read_latest() {
|
||||
return _v;
|
||||
}
|
||||
|
|
|
@ -10,6 +10,7 @@ public:
|
|||
float read_average();
|
||||
float read_latest();
|
||||
void set_pin(uint8_t p);
|
||||
float voltage_average();
|
||||
private:
|
||||
float _v;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue