ardupilot/libraries/AP_ADC/AP_ADC_ADS1115.h

44 lines
798 B
C
Raw Normal View History

#pragma once
2014-11-26 08:01:29 -04:00
#include <inttypes.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
2014-11-26 08:01:29 -04:00
#include "AP_ADC.h"
2014-11-26 08:01:29 -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();
~AP_ADC_ADS1115();
2014-11-26 08:01:29 -04:00
bool init();
size_t read(adc_report_s *report, size_t length) const;
uint8_t get_channels_number() const
2014-11-26 08:01:29 -04:00
{
return _channels_number;
}
private:
static const uint8_t _channels_number;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
2014-11-26 08:01:29 -04:00
uint32_t _last_update_timestamp;
uint16_t _gain;
int _channel_to_read;
adc_report_s *_samples;
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;
};