mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 22:48:29 -04:00
0c0a1b1dcc
this library abstracts out the way of getting an analog value. If the ADC library is being used then it calls the ADC Ch() method, otherwise it calls analogRead()
22 lines
424 B
C++
22 lines
424 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) {}
|
|
int read(void);
|
|
|
|
private:
|
|
AP_ADC * _adc;
|
|
int _ch;
|
|
float _prescale;
|
|
};
|
|
|
|
#endif // __AP_ANALOG_SOURCE_ADC_H__
|