2012-08-20 15:38:09 -03:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_AVR_ANALOG_IN_H__
|
|
|
|
#define __AP_HAL_AVR_ANALOG_IN_H__
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
2012-08-21 18:11:24 -03:00
|
|
|
#include "AP_HAL_AVR_Namespace.h"
|
2012-08-20 15:38:09 -03:00
|
|
|
|
2012-11-28 20:05:11 -04:00
|
|
|
#define AVR_INPUT_MAX_CHANNELS 12
|
2012-09-10 23:05:22 -03:00
|
|
|
|
|
|
|
class AP_HAL_AVR::ADCSource : public AP_HAL::AnalogSource {
|
|
|
|
public:
|
2012-11-28 20:05:11 -04:00
|
|
|
friend class AP_HAL_AVR::AVRAnalogIn;
|
2012-09-10 23:05:22 -03:00
|
|
|
/* pin designates the ADC input number, or when == AVR_ANALOG_PIN_VCC,
|
|
|
|
* board vcc */
|
|
|
|
ADCSource(uint8_t pin, float prescale = 1.0);
|
|
|
|
|
|
|
|
/* implement AnalogSource virtual api: */
|
2012-12-06 19:58:00 -04:00
|
|
|
float read_average();
|
|
|
|
float read_latest();
|
2012-12-04 18:51:17 -04:00
|
|
|
void set_pin(uint8_t p);
|
2012-09-10 23:05:22 -03:00
|
|
|
|
|
|
|
/* implementation specific interface: */
|
|
|
|
|
|
|
|
/* new_sample(): called with value of ADC measurments, from interrput */
|
|
|
|
void new_sample(uint16_t);
|
|
|
|
|
|
|
|
/* setup_read(): called to setup ADC registers for next measurment,
|
|
|
|
* from interrupt */
|
|
|
|
void setup_read();
|
|
|
|
|
|
|
|
/* read_average: called to calculate and clear the internal average.
|
2012-12-06 19:58:00 -04:00
|
|
|
* implements read_average(), unscaled. */
|
|
|
|
float _read_average();
|
2012-11-28 20:05:11 -04:00
|
|
|
|
2012-12-06 14:57:59 -04:00
|
|
|
int16_t get_pin() { return _pin; };
|
2012-09-10 23:05:22 -03:00
|
|
|
private:
|
2012-12-06 19:58:00 -04:00
|
|
|
/* following three are used from both an interrupt and normal thread */
|
2012-09-10 23:05:22 -03:00
|
|
|
volatile uint8_t _sum_count;
|
|
|
|
volatile uint16_t _sum;
|
2012-12-06 19:58:00 -04:00
|
|
|
volatile uint16_t _latest;
|
2012-09-10 23:05:22 -03:00
|
|
|
|
|
|
|
/* _pin designates the ADC input mux for the sample */
|
2012-12-04 18:51:17 -04:00
|
|
|
uint8_t _pin;
|
2012-09-10 23:05:22 -03:00
|
|
|
/* prescale scales the raw measurments for read()*/
|
|
|
|
const float _prescale;
|
|
|
|
};
|
|
|
|
|
|
|
|
/* AVRAnalogIn : a concrete class providing the implementations of the
|
2012-11-28 20:05:11 -04:00
|
|
|
* timer event and the AP_HAL::AnalogIn interface */
|
|
|
|
class AP_HAL_AVR::AVRAnalogIn : public AP_HAL::AnalogIn {
|
2012-08-20 15:38:09 -03:00
|
|
|
public:
|
2012-09-10 23:05:22 -03:00
|
|
|
AVRAnalogIn();
|
2012-11-28 20:05:11 -04:00
|
|
|
void init(void* ap_hal_scheduler);
|
2012-12-06 14:57:59 -04:00
|
|
|
AP_HAL::AnalogSource* channel(int16_t n);
|
|
|
|
AP_HAL::AnalogSource* channel(int16_t n, float prescale);
|
2012-11-28 20:05:11 -04:00
|
|
|
|
2012-09-10 23:05:22 -03:00
|
|
|
protected:
|
2012-12-06 14:57:59 -04:00
|
|
|
static ADCSource* _find_or_create_channel(int16_t num, float scale);
|
|
|
|
static ADCSource* _create_channel(int16_t num, float scale);
|
2012-09-10 23:05:22 -03:00
|
|
|
static void _register_channel(ADCSource*);
|
|
|
|
static void _timer_event(uint32_t);
|
|
|
|
static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS];
|
2012-12-06 14:57:59 -04:00
|
|
|
static int16_t _num_channels;
|
|
|
|
static int16_t _active_channel;
|
|
|
|
static int16_t _channel_repeat_count;
|
2012-09-10 23:05:22 -03:00
|
|
|
|
2012-08-20 15:38:09 -03:00
|
|
|
private:
|
2012-11-28 20:05:11 -04:00
|
|
|
ADCSource _vcc;
|
2012-08-20 15:38:09 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_AVR_ANALOG_IN_H__
|