ardupilot/libraries/AP_AnalogSource/AP_AnalogSource_Arduino.h
Andrew Tridgell 7c939e83e0 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
2011-12-17 07:29:09 +11:00

21 lines
476 B
C++

/// -*- 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__
#include "AnalogSource.h"
class AP_AnalogSource_Arduino : public AP_AnalogSource
{
public:
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__