ardupilot/libraries/AP_AnalogSource/AP_AnalogSource_ADC.h
Randy Mackay ffb4492c16 RangeFinder - small bug fix to initialise prescale variable.
Fixed up example sketch so it compiles and works again!
2011-12-10 16:25:41 +09:00

22 lines
445 B
C++

#ifndef __AP_ANALOG_SOURCE_ADC_H__
#define __AP_ANALOG_SOURCE_ADC_H__
#include "AnalogSource.h"
#include "../AP_ADC/AP_ADC.h"
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);
private:
AP_ADC * _adc;
int _ch;
float _prescale;
};
#endif // __AP_ANALOG_SOURCE_ADC_H__