APM:Libraries
AP_ADC_ADS1115.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <inttypes.h>
4 #include <AP_HAL/AP_HAL.h>
5 #include <AP_HAL/I2CDevice.h>
6 
7 #include "AP_ADC.h"
8 
10 {
11  uint8_t id;
12  float data;
13 };
14 
16 {
17 public:
19  ~AP_ADC_ADS1115();
20 
21  bool init();
22  size_t read(adc_report_s *report, size_t length) const;
23 
24  uint8_t get_channels_number() const
25  {
26  return _channels_number;
27  }
28 
29 private:
30  static const uint8_t _channels_number;
31 
33 
34  uint16_t _gain;
37 
38  void _update();
39  bool _start_conversion(uint8_t channel);
40 
41  float _convert_register_data_to_mv(int16_t word) const;
42 };
static const uint8_t _channels_number
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
uint8_t get_channels_number() const
adc_report_s * _samples
void init()
Generic board initialization function.
Definition: system.cpp:136