2012-10-11 13:39:27 -03:00
|
|
|
|
|
|
|
#ifndef __AP_ADC_ANALOG_SOURCE_H__
|
|
|
|
#define __AP_ADC_ANALOG_SOURCE_H__
|
|
|
|
|
|
|
|
#include <AP_ADC.h>
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
|
|
|
|
class AP_ADC_AnalogSource : public AP_HAL::AnalogSource
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_ADC_AnalogSource( AP_ADC * adc, uint8_t ch, float prescale = 1.0 ) :
|
|
|
|
_adc(adc), _ch(ch), _prescale(prescale)
|
|
|
|
{}
|
2012-12-06 21:35:59 -04:00
|
|
|
float read_average(void);
|
|
|
|
float read_latest(void);
|
2012-12-04 18:56:57 -04:00
|
|
|
void set_pin(uint8_t);
|
2013-03-03 01:13:19 -04:00
|
|
|
float voltage_average();
|
2013-05-13 02:13:59 -03:00
|
|
|
float voltage_average_ratiometric() { return voltage_average(); }
|
2012-10-11 13:39:27 -03:00
|
|
|
|
2013-05-02 22:11:40 -03:00
|
|
|
// stop pins not implemented on ADC yet
|
|
|
|
void set_stop_pin(uint8_t p) {}
|
|
|
|
void set_settle_time(uint16_t settle_time_ms) {}
|
|
|
|
|
2012-10-11 13:39:27 -03:00
|
|
|
private:
|
|
|
|
AP_ADC * _adc;
|
|
|
|
uint8_t _ch;
|
|
|
|
float _prescale;
|
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_ADC_ANALOG_SOURCE_H__
|