mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_ADC_AnalogSource: fix for new AnalogIn interface
This commit is contained in:
parent
a6d80af9ed
commit
8f99a12374
@ -1,12 +1,22 @@
|
|||||||
|
|
||||||
#include "AP_ADC_AnalogSource.h"
|
#include "AP_ADC_AnalogSource.h"
|
||||||
|
|
||||||
float AP_ADC_AnalogSource::read() {
|
/* Unfortunately we don't have a valid implementaton for read_latest - we
|
||||||
|
* only have access to the average from the ADC driver. Not really a big deal
|
||||||
|
* in our application currently. */
|
||||||
|
|
||||||
|
float AP_ADC_AnalogSource::read_latest() {
|
||||||
|
return read_average();
|
||||||
|
}
|
||||||
|
|
||||||
|
float AP_ADC_AnalogSource::read_average() {
|
||||||
float fullscale = _adc->Ch(_ch);
|
float fullscale = _adc->Ch(_ch);
|
||||||
float scaled = _prescale * fullscale;
|
float scaled = _prescale * fullscale;
|
||||||
return scaled;
|
return scaled;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void AP_ADC_AnalogSource::set_pin(uint8_t machtnichts) {
|
void AP_ADC_AnalogSource::set_pin(uint8_t machtnichts) {
|
||||||
/* it would be an error to call this
|
/* it would be an error to call this
|
||||||
* but for now we'll leave it a no-op. */
|
* but for now we'll leave it a no-op. */
|
||||||
|
@ -11,7 +11,8 @@ public:
|
|||||||
AP_ADC_AnalogSource( AP_ADC * adc, uint8_t ch, float prescale = 1.0 ) :
|
AP_ADC_AnalogSource( AP_ADC * adc, uint8_t ch, float prescale = 1.0 ) :
|
||||||
_adc(adc), _ch(ch), _prescale(prescale)
|
_adc(adc), _ch(ch), _prescale(prescale)
|
||||||
{}
|
{}
|
||||||
float read(void);
|
float read_average(void);
|
||||||
|
float read_latest(void);
|
||||||
void set_pin(uint8_t);
|
void set_pin(uint8_t);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
Loading…
Reference in New Issue
Block a user