ardupilot/libraries/AP_HAL_Linux/AnalogIn_ADS1115.h

49 lines
1.1 KiB
C
Raw Normal View History

#ifndef __ADS1115AnalogIn_H__
#define __ADS1115AnalogIn_H__
2014-11-26 08:03:06 -04:00
#include "AP_HAL_Linux.h"
#include <AP_ADC/AP_ADC.h>
2014-11-26 08:03:06 -04:00
#define ADS1115_ADC_MAX_CHANNELS 6
2014-11-26 08:03:06 -04:00
class ADS1115AnalogSource: public AP_HAL::AnalogSource {
2014-11-26 08:03:06 -04:00
public:
friend class ADS1115AnalogIn;
ADS1115AnalogSource(int16_t pin);
2014-11-26 08:03:06 -04:00
float read_average();
float read_latest();
void set_pin(uint8_t p);
void set_stop_pin(uint8_t p) {}
void set_settle_time(uint16_t settle_time_ms){}
float voltage_average();
float voltage_latest();
float voltage_average_ratiometric();
private:
int16_t _pin;
float _value;
};
class ADS1115AnalogIn: public AP_HAL::AnalogIn {
2014-11-26 08:03:06 -04:00
public:
ADS1115AnalogIn();
2014-11-26 08:03:06 -04:00
void init(void* implspecific);
AP_HAL::AnalogSource* channel(int16_t n);
/* Board voltage is not available */
float board_voltage(void)
{
return 0.0f;
}
private:
AP_ADC_ADS1115 *_adc;
ADS1115AnalogSource *_channels[ADS1115_ADC_MAX_CHANNELS];
2014-11-26 08:03:06 -04:00
uint8_t _channels_number;
void _update();
uint32_t _last_update_timestamp;
};
#endif