AP_ADC_ADS1115.cpp 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230
  1. #include <AP_HAL/AP_HAL.h>
  2. #include <AP_HAL/utility/sparse-endian.h>
  3. #include "AP_ADC_ADS1115.h"
  4. #define ADS1115_ADDRESS_ADDR_GND 0x48 // address pin low (GND)
  5. #define ADS1115_ADDRESS_ADDR_VDD 0x49 // address pin high (VCC)
  6. #define ADS1115_ADDRESS_ADDR_SDA 0x4A // address pin tied to SDA pin
  7. #define ADS1115_ADDRESS_ADDR_SCL 0x4B // address pin tied to SCL pin
  8. #define ADS1115_I2C_ADDR ADS1115_ADDRESS_ADDR_GND
  9. #define ADS1115_I2C_BUS 1
  10. #define ADS1115_RA_CONVERSION 0x00
  11. #define ADS1115_RA_CONFIG 0x01
  12. #define ADS1115_RA_LO_THRESH 0x02
  13. #define ADS1115_RA_HI_THRESH 0x03
  14. #define ADS1115_OS_SHIFT 15
  15. #define ADS1115_OS_INACTIVE 0x00 << ADS1115_OS_SHIFT
  16. #define ADS1115_OS_ACTIVE 0x01 << ADS1115_OS_SHIFT
  17. #define ADS1115_MUX_SHIFT 12
  18. #define ADS1115_MUX_P0_N1 0x00 << ADS1115_MUX_SHIFT /* default */
  19. #define ADS1115_MUX_P0_N3 0x01 << ADS1115_MUX_SHIFT
  20. #define ADS1115_MUX_P1_N3 0x02 << ADS1115_MUX_SHIFT
  21. #define ADS1115_MUX_P2_N3 0x03 << ADS1115_MUX_SHIFT
  22. #define ADS1115_MUX_P0_NG 0x04 << ADS1115_MUX_SHIFT
  23. #define ADS1115_MUX_P1_NG 0x05 << ADS1115_MUX_SHIFT
  24. #define ADS1115_MUX_P2_NG 0x06 << ADS1115_MUX_SHIFT
  25. #define ADS1115_MUX_P3_NG 0x07 << ADS1115_MUX_SHIFT
  26. #define ADS1115_PGA_SHIFT 9
  27. #define ADS1115_PGA_6P144 0x00 << ADS1115_PGA_SHIFT
  28. #define ADS1115_PGA_4P096 0x01 << ADS1115_PGA_SHIFT
  29. #define ADS1115_PGA_2P048 0x02 << ADS1115_PGA_SHIFT // default
  30. #define ADS1115_PGA_1P024 0x03 << ADS1115_PGA_SHIFT
  31. #define ADS1115_PGA_0P512 0x04 << ADS1115_PGA_SHIFT
  32. #define ADS1115_PGA_0P256 0x05 << ADS1115_PGA_SHIFT
  33. #define ADS1115_PGA_0P256B 0x06 << ADS1115_PGA_SHIFT
  34. #define ADS1115_PGA_0P256C 0x07 << ADS1115_PGA_SHIFT
  35. #define ADS1115_MV_6P144 0.187500f
  36. #define ADS1115_MV_4P096 0.125000f
  37. #define ADS1115_MV_2P048 0.062500f // default
  38. #define ADS1115_MV_1P024 0.031250f
  39. #define ADS1115_MV_0P512 0.015625f
  40. #define ADS1115_MV_0P256 0.007813f
  41. #define ADS1115_MV_0P256B 0.007813f
  42. #define ADS1115_MV_0P256C 0.007813f
  43. #define ADS1115_MODE_SHIFT 8
  44. #define ADS1115_MODE_CONTINUOUS 0x00 << ADS1115_MODE_SHIFT
  45. #define ADS1115_MODE_SINGLESHOT 0x01 << ADS1115_MODE_SHIFT // default
  46. #define ADS1115_RATE_SHIFT 5
  47. #define ADS1115_RATE_8 0x00 << ADS1115_RATE_SHIFT
  48. #define ADS1115_RATE_16 0x01 << ADS1115_RATE_SHIFT
  49. #define ADS1115_RATE_32 0x02 << ADS1115_RATE_SHIFT
  50. #define ADS1115_RATE_64 0x03 << ADS1115_RATE_SHIFT
  51. #define ADS1115_RATE_128 0x04 << ADS1115_RATE_SHIFT // default
  52. #define ADS1115_RATE_250 0x05 << ADS1115_RATE_SHIFT
  53. #define ADS1115_RATE_475 0x06 << ADS1115_RATE_SHIFT
  54. #define ADS1115_RATE_860 0x07 << ADS1115_RATE_SHIFT
  55. #define ADS1115_COMP_MODE_SHIFT 4
  56. #define ADS1115_COMP_MODE_HYSTERESIS 0x00 << ADS1115_COMP_MODE_SHIFT // default
  57. #define ADS1115_COMP_MODE_WINDOW 0x01 << ADS1115_COMP_MODE_SHIFT
  58. #define ADS1115_COMP_POL_SHIFT 3
  59. #define ADS1115_COMP_POL_ACTIVE_LOW 0x00 << ADS1115_COMP_POL_SHIFT // default
  60. #define ADS1115_COMP_POL_ACTIVE_HIGH 0x01 << ADS1115_COMP_POL_SHIFT
  61. #define ADS1115_COMP_LAT_SHIFT 2
  62. #define ADS1115_COMP_LAT_NON_LATCHING 0x00 << ADS1115_COMP_LAT_SHIFT // default
  63. #define ADS1115_COMP_LAT_LATCHING 0x01 << ADS1115_COMP_LAT_SHIFT
  64. #define ADS1115_COMP_QUE_SHIFT 0
  65. #define ADS1115_COMP_QUE_ASSERT1 0x00 << ADS1115_COMP_SHIFT
  66. #define ADS1115_COMP_QUE_ASSERT2 0x01 << ADS1115_COMP_SHIFT
  67. #define ADS1115_COMP_QUE_ASSERT4 0x02 << ADS1115_COMP_SHIFT
  68. #define ADS1115_COMP_QUE_DISABLE 0x03 // default
  69. #define ADS1115_DEBUG 0
  70. #if ADS1115_DEBUG
  71. #include <cstdio>
  72. #define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  73. #define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  74. #else
  75. #define debug(fmt, args ...)
  76. #define error(fmt, args ...)
  77. #endif
  78. extern const AP_HAL::HAL &hal;
  79. #define ADS1115_CHANNELS_COUNT 6
  80. const uint8_t AP_ADC_ADS1115::_channels_number = ADS1115_CHANNELS_COUNT;
  81. /* Only two differential channels used */
  82. static const uint16_t mux_table[ADS1115_CHANNELS_COUNT] = {
  83. ADS1115_MUX_P1_N3,
  84. ADS1115_MUX_P2_N3,
  85. ADS1115_MUX_P0_NG,
  86. ADS1115_MUX_P1_NG,
  87. ADS1115_MUX_P2_NG,
  88. ADS1115_MUX_P3_NG
  89. };
  90. AP_ADC_ADS1115::AP_ADC_ADS1115()
  91. : _dev{}
  92. , _gain(ADS1115_PGA_4P096)
  93. , _channel_to_read(0)
  94. {
  95. _samples = new adc_report_s[_channels_number];
  96. }
  97. AP_ADC_ADS1115::~AP_ADC_ADS1115()
  98. {
  99. delete[] _samples;
  100. }
  101. bool AP_ADC_ADS1115::init()
  102. {
  103. _dev = hal.i2c_mgr->get_device(ADS1115_I2C_BUS, ADS1115_I2C_ADDR);
  104. if (!_dev) {
  105. return false;
  106. }
  107. _gain = ADS1115_PGA_4P096;
  108. _dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_ADC_ADS1115::_update, void));
  109. return true;
  110. }
  111. bool AP_ADC_ADS1115::_start_conversion(uint8_t channel)
  112. {
  113. struct PACKED {
  114. uint8_t reg;
  115. be16_t val;
  116. } config;
  117. config.reg = ADS1115_RA_CONFIG;
  118. config.val = htobe16(ADS1115_OS_ACTIVE | _gain | mux_table[channel] |
  119. ADS1115_MODE_SINGLESHOT | ADS1115_COMP_QUE_DISABLE |
  120. ADS1115_RATE_250);
  121. return _dev->transfer((uint8_t *)&config, sizeof(config), nullptr, 0);
  122. }
  123. size_t AP_ADC_ADS1115::read(adc_report_s *report, size_t length) const
  124. {
  125. for (size_t i = 0; i < length; i++) {
  126. report[i].data = _samples[i].data;
  127. report[i].id = _samples[i].id;
  128. }
  129. return length;
  130. }
  131. float AP_ADC_ADS1115::_convert_register_data_to_mv(int16_t word) const
  132. {
  133. float pga;
  134. switch (_gain) {
  135. case ADS1115_PGA_6P144:
  136. pga = ADS1115_MV_6P144;
  137. break;
  138. case ADS1115_PGA_4P096:
  139. pga = ADS1115_MV_4P096;
  140. break;
  141. case ADS1115_PGA_2P048:
  142. pga = ADS1115_MV_2P048;
  143. break;
  144. case ADS1115_PGA_1P024:
  145. pga = ADS1115_MV_1P024;
  146. break;
  147. case ADS1115_PGA_0P512:
  148. pga = ADS1115_MV_0P512;
  149. break;
  150. case ADS1115_PGA_0P256:
  151. pga = ADS1115_MV_0P256;
  152. break;
  153. case ADS1115_PGA_0P256B:
  154. pga = ADS1115_MV_0P256B;
  155. break;
  156. case ADS1115_PGA_0P256C:
  157. pga = ADS1115_MV_0P256C;
  158. break;
  159. default:
  160. pga = 0.0f;
  161. hal.console->printf("Wrong gain");
  162. AP_HAL::panic("ADS1115: wrong gain selected");
  163. break;
  164. }
  165. return (float) word * pga;
  166. }
  167. void AP_ADC_ADS1115::_update()
  168. {
  169. uint8_t config[2];
  170. be16_t val;
  171. if (!_dev->read_registers(ADS1115_RA_CONFIG, config, sizeof(config))) {
  172. error("_dev->read_registers failed in ADS1115");
  173. return;
  174. }
  175. /* check rdy bit */
  176. if ((config[1] & 0x80) != 0x80 ) {
  177. return;
  178. }
  179. if (!_dev->read_registers(ADS1115_RA_CONVERSION, (uint8_t *)&val, sizeof(val))) {
  180. return;
  181. }
  182. float sample = _convert_register_data_to_mv(be16toh(val));
  183. _samples[_channel_to_read].data = sample;
  184. _samples[_channel_to_read].id = _channel_to_read;
  185. /* select next channel */
  186. _channel_to_read = (_channel_to_read + 1) % _channels_number;
  187. _start_conversion(_channel_to_read);
  188. }