mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_AnalogSource: make read_average() return a float
this allows it to take advantage of better than 1 bit resolution by averaging
This commit is contained in:
parent
4b5d98e65b
commit
a361a3aebd
@ -104,7 +104,7 @@ uint16_t AP_AnalogSource_Arduino::read_vcc(void)
|
||||
// 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
|
||||
uint16_t AP_AnalogSource_Arduino::read_average(void)
|
||||
float AP_AnalogSource_Arduino::read_average(void)
|
||||
{
|
||||
uint16_t sum;
|
||||
uint8_t sum_count;
|
||||
@ -119,7 +119,7 @@ uint16_t AP_AnalogSource_Arduino::read_average(void)
|
||||
pins[_pin_index].sum = 0;
|
||||
pins[_pin_index].sum_count = 0;
|
||||
sei();
|
||||
return sum / sum_count;
|
||||
return sum / (float)sum_count;
|
||||
}
|
||||
|
||||
// read with the prescaler. This uses the averaged value since
|
||||
|
@ -32,7 +32,7 @@ class AP_AnalogSource_Arduino : public AP_AnalogSource
|
||||
|
||||
// read the average 16 bit ADC value since
|
||||
// we last called read_average().
|
||||
uint16_t read_average(void);
|
||||
float read_average(void);
|
||||
|
||||
private:
|
||||
uint8_t _pin_index;
|
||||
|
Loading…
Reference in New Issue
Block a user