2016-01-28 16:12:12 -04:00
|
|
|
#pragma once
|
2014-11-26 08:01:29 -04:00
|
|
|
|
|
|
|
#include <inttypes.h>
|
2015-08-11 03:28:41 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-04-18 13:02:52 -03:00
|
|
|
#include <AP_HAL/I2CDevice.h>
|
2014-11-26 08:01:29 -04:00
|
|
|
|
2016-01-28 16:12:12 -04:00
|
|
|
struct adc_report_s
|
2014-11-26 08:01:29 -04:00
|
|
|
{
|
|
|
|
uint8_t id;
|
|
|
|
float data;
|
|
|
|
};
|
|
|
|
|
|
|
|
class AP_ADC_ADS1115
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_ADC_ADS1115();
|
2016-08-02 17:28:28 -03:00
|
|
|
~AP_ADC_ADS1115();
|
2014-11-26 08:01:29 -04:00
|
|
|
|
|
|
|
bool init();
|
|
|
|
size_t read(adc_report_s *report, size_t length) const;
|
|
|
|
|
2016-01-28 16:12:12 -04:00
|
|
|
uint8_t get_channels_number() const
|
2014-11-26 08:01:29 -04:00
|
|
|
{
|
|
|
|
return _channels_number;
|
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
|
|
|
static const uint8_t _channels_number;
|
|
|
|
|
2016-07-27 01:39:23 -03:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
|
|
|
|
|
2014-11-26 08:01:29 -04:00
|
|
|
uint16_t _gain;
|
|
|
|
int _channel_to_read;
|
|
|
|
adc_report_s *_samples;
|
|
|
|
|
2017-01-13 15:26:14 -04:00
|
|
|
void _update();
|
2014-11-26 08:01:29 -04:00
|
|
|
bool _start_conversion(uint8_t channel);
|
|
|
|
|
|
|
|
float _convert_register_data_to_mv(int16_t word) const;
|
|
|
|
};
|