AnalogSource: return a float from read() method

this gives the full resolution when using the ADC backend. It also
adds scaling for the Arduino backend
This commit is contained in:
Andrew Tridgell 2011-12-17 07:18:29 +11:00
parent 4bbd5392ef
commit 7c939e83e0
5 changed files with 15 additions and 9 deletions

View File

@ -1,9 +1,9 @@
#include "AP_AnalogSource_ADC.h"
int AP_AnalogSource_ADC::read(void)
float AP_AnalogSource_ADC::read(void)
{
int fullscale = _adc->Ch(_ch);
int scaled = _prescale * fullscale;
float fullscale = _adc->Ch(_ch);
float scaled = _prescale * fullscale;
return scaled;
}

View File

@ -10,7 +10,7 @@ class AP_AnalogSource_ADC : public AP_AnalogSource
public:
AP_AnalogSource_ADC( AP_ADC * adc, int ch, float prescale = 1.0 ) :
_adc(adc), _ch(ch), _prescale(prescale) {}
int read(void);
float read(void);
private:
AP_ADC * _adc;

View File

@ -1,8 +1,11 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "wiring.h"
#include "AP_AnalogSource_Arduino.h"
int AP_AnalogSource_Arduino::read(void)
float AP_AnalogSource_Arduino::read(void)
{
return analogRead(_pin);
float fullscale = analogRead(_pin);
float scaled = _prescale * fullscale;
return scaled;
}

View File

@ -1,3 +1,4 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef __AP_ANALOG_SOURCE_ARDUINO_H__
#define __AP_ANALOG_SOURCE_ARDUINO_H__
@ -7,11 +8,13 @@
class AP_AnalogSource_Arduino : public AP_AnalogSource
{
public:
AP_AnalogSource_Arduino( int pin ) : _pin(pin) {}
int read(void);
AP_AnalogSource_Arduino( int pin, float prescale = 1.0 ) :
_pin(pin), _prescale(prescale) {}
float read(void);
private:
int _pin;
float _prescale;
};
#endif // __AP_ANALOG_SOURCE_ARDUINO_H__

View File

@ -5,7 +5,7 @@
class AP_AnalogSource
{
public:
virtual int read(void) = 0;
virtual float read(void) = 0;
};
#endif // __ANALOG_SOURCE_H__