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 11 #define ADS1115_I2C_ADDR ADS1115_ADDRESS_ADDR_GND 12 #define ADS1115_I2C_BUS 1 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 19 #define ADS1115_OS_SHIFT 15 20 #define ADS1115_OS_INACTIVE 0x00 << ADS1115_OS_SHIFT 21 #define ADS1115_OS_ACTIVE 0x01 << ADS1115_OS_SHIFT 23 #define ADS1115_MUX_SHIFT 12 24 #define ADS1115_MUX_P0_N1 0x00 << ADS1115_MUX_SHIFT 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 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 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 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 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 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 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 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 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 84 #define ADS1115_DEBUG 0 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) 90 #define debug(fmt, args ...) 91 #define error(fmt, args ...) 96 #define ADS1115_CHANNELS_COUNT 6 150 return _dev->
transfer((uint8_t *)&config,
sizeof(config),
nullptr, 0);
155 for (
size_t i = 0; i < length; i++) {
200 return (
float) word * pga;
209 error(
"_dev->read_registers failed in ADS1115");
214 if ((config[1] & 0x80) != 0x80 ) {
#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
AP_HAL::UARTDriver * console
#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_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
static uint16_t be16toh(be16_t value)
#define ADS1115_RA_CONVERSION
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
#define ADS1115_MUX_P1_NG
static be16_t htobe16(uint16_t value)
#define ADS1115_MUX_P3_NG
#define ADS1115_MODE_SINGLESHOT
AP_HAL::I2CDeviceManager * i2c_mgr
#define ADS1115_COMP_QUE_DISABLE
static const uint16_t mux_table[ADS1115_CHANNELS_COUNT]
#define error(fmt, args ...)
float _convert_register_data_to_mv(int16_t word) const
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void panic(const char *errormsg,...) FMT_PRINTF(1
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