2011-12-16 16:18:29 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2011-11-12 23:14:55 -04:00
|
|
|
|
|
|
|
#ifndef __AP_ANALOG_SOURCE_ARDUINO_H__
|
|
|
|
#define __AP_ANALOG_SOURCE_ARDUINO_H__
|
|
|
|
|
|
|
|
#include "AnalogSource.h"
|
2012-06-29 08:48:34 -03:00
|
|
|
#include "AP_PeriodicProcess.h"
|
|
|
|
|
|
|
|
// special pin number which is interpreted as a
|
|
|
|
// internal Vcc voltage read
|
2012-11-06 06:45:40 -04:00
|
|
|
#define ANALOG_PIN_VCC 254
|
|
|
|
#define ANALOG_PIN_NONE 255
|
2011-11-12 23:14:55 -04:00
|
|
|
|
|
|
|
class AP_AnalogSource_Arduino : public AP_AnalogSource
|
|
|
|
{
|
2012-08-17 03:08:47 -03:00
|
|
|
public:
|
2012-06-29 08:48:34 -03:00
|
|
|
AP_AnalogSource_Arduino( uint8_t pin, float prescale = 1.0 ) :
|
|
|
|
_prescale(prescale) {
|
2012-10-16 03:20:15 -03:00
|
|
|
_assign_pin_index(pin);
|
2012-06-29 08:48:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// setup the timer callback
|
2012-08-17 03:08:47 -03:00
|
|
|
static void init_timer(AP_PeriodicProcess * scheduler);
|
2012-06-29 08:48:34 -03:00
|
|
|
|
|
|
|
// read a value with a prescale
|
2012-08-17 03:08:47 -03:00
|
|
|
float read(void);
|
2011-11-12 23:14:55 -04:00
|
|
|
|
2012-06-29 08:48:34 -03:00
|
|
|
// read the raw 16 bit ADC value
|
2012-08-17 03:08:47 -03:00
|
|
|
uint16_t read_raw(void);
|
2012-06-29 08:48:34 -03:00
|
|
|
|
|
|
|
// read a Vcc value in millivolts
|
2012-08-17 03:08:47 -03:00
|
|
|
uint16_t read_vcc(void);
|
2012-06-29 08:48:34 -03:00
|
|
|
|
|
|
|
// read the average 16 bit ADC value since
|
|
|
|
// we last called read_average().
|
2012-08-17 03:08:47 -03:00
|
|
|
float read_average(void);
|
2012-06-29 08:48:34 -03:00
|
|
|
|
2012-10-16 03:20:15 -03:00
|
|
|
// set the pin to be used for this source. This allows for the pin
|
|
|
|
// to be changed at runtime
|
|
|
|
void set_pin(uint8_t pin);
|
|
|
|
|
2012-08-17 03:08:47 -03:00
|
|
|
private:
|
|
|
|
uint8_t _pin_index;
|
|
|
|
float _prescale;
|
2012-06-29 08:48:34 -03:00
|
|
|
|
2012-10-16 03:20:15 -03:00
|
|
|
uint8_t _remap_pin(uint8_t pin);
|
|
|
|
void _assign_pin_index(uint8_t pin);
|
2011-11-12 23:14:55 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_ANALOG_SOURCE_ARDUINO_H__
|