ardupilot/libraries/AP_ADC/AP_ADC_ADS1115.h
Peter Barker b6191578dc AP_ADC: correct compilter warnings
../../libraries/AP_ADC/AP_ADC_ADS1115.h:34:25: warning: private field
'_last_update_timestamp' is not used [-Wunused-private-field]
    uint32_t            _last_update_timestamp;
                        ^
1 warning generated.
2018-03-02 09:26:37 +09:00

43 lines
750 B
C++

#pragma once
#include <inttypes.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include "AP_ADC.h"
struct adc_report_s
{
uint8_t id;
float data;
};
class AP_ADC_ADS1115
{
public:
AP_ADC_ADS1115();
~AP_ADC_ADS1115();
bool init();
size_t read(adc_report_s *report, size_t length) const;
uint8_t get_channels_number() const
{
return _channels_number;
}
private:
static const uint8_t _channels_number;
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
uint16_t _gain;
int _channel_to_read;
adc_report_s *_samples;
void _update();
bool _start_conversion(uint8_t channel);
float _convert_register_data_to_mv(int16_t word) const;
};