APM:Libraries
AP_ADC_ADS1115.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
3 
4 #include "AP_ADC_ADS1115.h"
5 
6 #define ADS1115_ADDRESS_ADDR_GND 0x48 // address pin low (GND)
7 #define ADS1115_ADDRESS_ADDR_VDD 0x49 // address pin high (VCC)
8 #define ADS1115_ADDRESS_ADDR_SDA 0x4A // address pin tied to SDA pin
9 #define ADS1115_ADDRESS_ADDR_SCL 0x4B // address pin tied to SCL pin
10 
11 #define ADS1115_I2C_ADDR ADS1115_ADDRESS_ADDR_GND
12 #define ADS1115_I2C_BUS 1
13 
14 #define ADS1115_RA_CONVERSION 0x00
15 #define ADS1115_RA_CONFIG 0x01
16 #define ADS1115_RA_LO_THRESH 0x02
17 #define ADS1115_RA_HI_THRESH 0x03
18 
19 #define ADS1115_OS_SHIFT 15
20 #define ADS1115_OS_INACTIVE 0x00 << ADS1115_OS_SHIFT
21 #define ADS1115_OS_ACTIVE 0x01 << ADS1115_OS_SHIFT
22 
23 #define ADS1115_MUX_SHIFT 12
24 #define ADS1115_MUX_P0_N1 0x00 << ADS1115_MUX_SHIFT /* default */
25 #define ADS1115_MUX_P0_N3 0x01 << ADS1115_MUX_SHIFT
26 #define ADS1115_MUX_P1_N3 0x02 << ADS1115_MUX_SHIFT
27 #define ADS1115_MUX_P2_N3 0x03 << ADS1115_MUX_SHIFT
28 #define ADS1115_MUX_P0_NG 0x04 << ADS1115_MUX_SHIFT
29 #define ADS1115_MUX_P1_NG 0x05 << ADS1115_MUX_SHIFT
30 #define ADS1115_MUX_P2_NG 0x06 << ADS1115_MUX_SHIFT
31 #define ADS1115_MUX_P3_NG 0x07 << ADS1115_MUX_SHIFT
32 
33 #define ADS1115_PGA_SHIFT 9
34 #define ADS1115_PGA_6P144 0x00 << ADS1115_PGA_SHIFT
35 #define ADS1115_PGA_4P096 0x01 << ADS1115_PGA_SHIFT
36 #define ADS1115_PGA_2P048 0x02 << ADS1115_PGA_SHIFT // default
37 #define ADS1115_PGA_1P024 0x03 << ADS1115_PGA_SHIFT
38 #define ADS1115_PGA_0P512 0x04 << ADS1115_PGA_SHIFT
39 #define ADS1115_PGA_0P256 0x05 << ADS1115_PGA_SHIFT
40 #define ADS1115_PGA_0P256B 0x06 << ADS1115_PGA_SHIFT
41 #define ADS1115_PGA_0P256C 0x07 << ADS1115_PGA_SHIFT
42 
43 #define ADS1115_MV_6P144 0.187500f
44 #define ADS1115_MV_4P096 0.125000f
45 #define ADS1115_MV_2P048 0.062500f // default
46 #define ADS1115_MV_1P024 0.031250f
47 #define ADS1115_MV_0P512 0.015625f
48 #define ADS1115_MV_0P256 0.007813f
49 #define ADS1115_MV_0P256B 0.007813f
50 #define ADS1115_MV_0P256C 0.007813f
51 
52 #define ADS1115_MODE_SHIFT 8
53 #define ADS1115_MODE_CONTINUOUS 0x00 << ADS1115_MODE_SHIFT
54 #define ADS1115_MODE_SINGLESHOT 0x01 << ADS1115_MODE_SHIFT // default
55 
56 #define ADS1115_RATE_SHIFT 5
57 #define ADS1115_RATE_8 0x00 << ADS1115_RATE_SHIFT
58 #define ADS1115_RATE_16 0x01 << ADS1115_RATE_SHIFT
59 #define ADS1115_RATE_32 0x02 << ADS1115_RATE_SHIFT
60 #define ADS1115_RATE_64 0x03 << ADS1115_RATE_SHIFT
61 #define ADS1115_RATE_128 0x04 << ADS1115_RATE_SHIFT // default
62 #define ADS1115_RATE_250 0x05 << ADS1115_RATE_SHIFT
63 #define ADS1115_RATE_475 0x06 << ADS1115_RATE_SHIFT
64 #define ADS1115_RATE_860 0x07 << ADS1115_RATE_SHIFT
65 
66 #define ADS1115_COMP_MODE_SHIFT 4
67 #define ADS1115_COMP_MODE_HYSTERESIS 0x00 << ADS1115_COMP_MODE_SHIFT // default
68 #define ADS1115_COMP_MODE_WINDOW 0x01 << ADS1115_COMP_MODE_SHIFT
69 
70 #define ADS1115_COMP_POL_SHIFT 3
71 #define ADS1115_COMP_POL_ACTIVE_LOW 0x00 << ADS1115_COMP_POL_SHIFT // default
72 #define ADS1115_COMP_POL_ACTIVE_HIGH 0x01 << ADS1115_COMP_POL_SHIFT
73 
74 #define ADS1115_COMP_LAT_SHIFT 2
75 #define ADS1115_COMP_LAT_NON_LATCHING 0x00 << ADS1115_COMP_LAT_SHIFT // default
76 #define ADS1115_COMP_LAT_LATCHING 0x01 << ADS1115_COMP_LAT_SHIFT
77 
78 #define ADS1115_COMP_QUE_SHIFT 0
79 #define ADS1115_COMP_QUE_ASSERT1 0x00 << ADS1115_COMP_SHIFT
80 #define ADS1115_COMP_QUE_ASSERT2 0x01 << ADS1115_COMP_SHIFT
81 #define ADS1115_COMP_QUE_ASSERT4 0x02 << ADS1115_COMP_SHIFT
82 #define ADS1115_COMP_QUE_DISABLE 0x03 // default
83 
84 #define ADS1115_DEBUG 0
85 #if ADS1115_DEBUG
86 #include <cstdio>
87 #define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
88 #define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
89 #else
90 #define debug(fmt, args ...)
91 #define error(fmt, args ...)
92 #endif
93 
94 extern const AP_HAL::HAL &hal;
95 
96 #define ADS1115_CHANNELS_COUNT 6
97 
99 
100 /* Only two differential channels used */
101 static const uint16_t mux_table[ADS1115_CHANNELS_COUNT] = {
108 };
109 
110 
112  : _dev{}
114  , _channel_to_read(0)
115 {
117 }
118 
120 {
121  delete[] _samples;
122 }
123 
125 {
127  if (!_dev) {
128  return false;
129  }
130 
132 
134 
135  return true;
136 }
137 
139 {
140  struct PACKED {
141  uint8_t reg;
142  be16_t val;
143  } config;
144 
145  config.reg = ADS1115_RA_CONFIG;
146  config.val = htobe16(ADS1115_OS_ACTIVE | _gain | mux_table[channel] |
149 
150  return _dev->transfer((uint8_t *)&config, sizeof(config), nullptr, 0);
151 }
152 
153 size_t AP_ADC_ADS1115::read(adc_report_s *report, size_t length) const
154 {
155  for (size_t i = 0; i < length; i++) {
156  report[i].data = _samples[i].data;
157  report[i].id = _samples[i].id;
158  }
159 
160  return length;
161 }
162 
164 {
165 
166  float pga;
167 
168  switch (_gain) {
169  case ADS1115_PGA_6P144:
170  pga = ADS1115_MV_6P144;
171  break;
172  case ADS1115_PGA_4P096:
173  pga = ADS1115_MV_4P096;
174  break;
175  case ADS1115_PGA_2P048:
176  pga = ADS1115_MV_2P048;
177  break;
178  case ADS1115_PGA_1P024:
179  pga = ADS1115_MV_1P024;
180  break;
181  case ADS1115_PGA_0P512:
182  pga = ADS1115_MV_0P512;
183  break;
184  case ADS1115_PGA_0P256:
185  pga = ADS1115_MV_0P256;
186  break;
187  case ADS1115_PGA_0P256B:
188  pga = ADS1115_MV_0P256B;
189  break;
190  case ADS1115_PGA_0P256C:
191  pga = ADS1115_MV_0P256C;
192  break;
193  default:
194  pga = 0.0f;
195  hal.console->printf("Wrong gain");
196  AP_HAL::panic("ADS1115: wrong gain selected");
197  break;
198  }
199 
200  return (float) word * pga;
201 }
202 
204 {
205  uint8_t config[2];
206  be16_t val;
207 
208  if (!_dev->read_registers(ADS1115_RA_CONFIG, config, sizeof(config))) {
209  error("_dev->read_registers failed in ADS1115");
210  return;
211  }
212 
213  /* check rdy bit */
214  if ((config[1] & 0x80) != 0x80 ) {
215  return;
216  }
217 
218  if (!_dev->read_registers(ADS1115_RA_CONVERSION, (uint8_t *)&val, sizeof(val))) {
219  return;
220  }
221 
222  float sample = _convert_register_data_to_mv(be16toh(val));
223 
224  _samples[_channel_to_read].data = sample;
226 
227  /* select next channel */
230 }
#define ADS1115_MV_0P256C
#define ADS1115_PGA_6P144
bool _start_conversion(uint8_t channel)
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
#define ADS1115_MUX_P1_N3
#define ADS1115_PGA_1P024
#define ADS1115_I2C_ADDR
#define ADS1115_RATE_250
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define ADS1115_PGA_0P512
#define ADS1115_PGA_0P256B
size_t read(adc_report_s *report, size_t length) const
#define ADS1115_CHANNELS_COUNT
#define ADS1115_MV_0P256B
#define ADS1115_MV_0P256
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define ADS1115_MUX_P2_NG
static const uint8_t _channels_number
#define ADS1115_OS_ACTIVE
#define ADS1115_PGA_0P256C
#define ADS1115_MUX_P0_NG
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define ADS1115_MV_4P096
static uint16_t be16toh(be16_t value)
Definition: sparse-endian.h:83
#define ADS1115_RA_CONVERSION
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
#define ADS1115_I2C_BUS
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
#define ADS1115_MUX_P1_NG
static be16_t htobe16(uint16_t value)
Definition: sparse-endian.h:75
#define ADS1115_MUX_P3_NG
#define ADS1115_MODE_SINGLESHOT
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
#define ADS1115_COMP_QUE_DISABLE
static const uint16_t mux_table[ADS1115_CHANNELS_COUNT]
#define ADS1115_MV_6P144
adc_report_s * _samples
#define ADS1115_MV_2P048
#define error(fmt, args ...)
float _convert_register_data_to_mv(int16_t word) const
#define PACKED
Definition: AP_Common.h:28
#define ADS1115_MV_1P024
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
#define ADS1115_MUX_P2_N3
#define ADS1115_PGA_4P096
#define ADS1115_PGA_0P256
#define ADS1115_RA_CONFIG
#define ADS1115_PGA_2P048
uint16_t __ap_bitwise be16_t
Definition: sparse-endian.h:36
#define ADS1115_MV_0P512