ardupilot/libraries/AP_HAL_Linux/AnalogIn_ADS1115.h

42 lines
1011 B
C
Raw Normal View History

#pragma once
2014-11-26 08:03:06 -04:00
#include "AP_HAL_Linux.h"
#include <AP_ADC/AP_ADC_ADS1115.h>
2014-11-26 08:03:06 -04:00
#define ADS1115_ADC_MAX_CHANNELS 6
2014-11-26 08:03:06 -04:00
class AnalogSource_ADS1115: public AP_HAL::AnalogSource {
2014-11-26 08:03:06 -04:00
public:
friend class AnalogIn_ADS1115;
AnalogSource_ADS1115(int16_t pin);
float read_average() override;
float read_latest() override;
bool set_pin(uint8_t p) override;
float voltage_average() override;
float voltage_latest() override;
float voltage_average_ratiometric() override;
2014-11-26 08:03:06 -04:00
private:
int16_t _pin;
float _value;
};
class AnalogIn_ADS1115: public AP_HAL::AnalogIn {
2014-11-26 08:03:06 -04:00
public:
AnalogIn_ADS1115();
void init() override;
AP_HAL::AnalogSource *channel(int16_t n) override;
2014-11-26 08:03:06 -04:00
/* Board voltage is not available */
float board_voltage() override { return 5.0f; }
2014-11-26 08:03:06 -04:00
private:
uint8_t _channels_number;
void _update();
AP_ADC_ADS1115 *_adc;
AnalogSource_ADS1115 *_channels[ADS1115_ADC_MAX_CHANNELS];
uint32_t _last_update_timestamp;
HAL_Semaphore _semaphore;
2014-11-26 08:03:06 -04:00
};