ADS7138 I2C ADC

The Ads7138 class implements support for the Texas Instruments ADS7138 12-bit 8-channel ADC. The ADS7138 is a 12-bit, 8-channel, low-power, successive approximation register (SAR) analog-to-digital converter (ADC) which can configure any of its 8 channels as single-ended analog inputs, digital inputs, or digital outputs. It has an operating mode that allows the user to configure the device for a single conversion, or to automatically convert on a continuous basis.

API Reference

Header File

Classes

class Ads7138 : public espp::BasePeripheral<>

Class for reading values from the ADS7138 family of ADC chips.

The ADS7138 is a 16-bit, 8-channel ADC with 8 digital I/O pins. It supports a variety of sampling modes, including autonomous sampling, manual sampling, and auto sequence sampling. It also supports oversampling ratios of 2, 4, 8, 16, 32, 64, and 128. It additionally allows the user to configure the analog or digital inputs to trigger an alert when the value goes above or below a threshold (enter or leave a region of voltage).

ADS7138 Example

    static constexpr gpio_num_t ALERT_PIN = (gpio_num_t)CONFIG_EXAMPLE_ALERT_GPIO;
    // make the I2C that we'll use to communicate
    espp::I2c i2c({
        .port = I2C_NUM_1,
        .sda_io_num = (gpio_num_t)CONFIG_EXAMPLE_I2C_SDA_GPIO,
        .scl_io_num = (gpio_num_t)CONFIG_EXAMPLE_I2C_SCL_GPIO,
    });

    // make the actual ads class
    static int select_bit_mask = (1 << 5);
    espp::Ads7138 ads(espp::Ads7138::Config{
        .device_address = espp::Ads7138::DEFAULT_ADDRESS,
        .mode = espp::Ads7138::Mode::AUTONOMOUS,
        .analog_inputs = {espp::Ads7138::Channel::CH1, espp::Ads7138::Channel::CH3},
        .digital_inputs = {espp::Ads7138::Channel::CH5},
        .digital_outputs =
            {espp::Ads7138::Channel::CH7}, // On the BP-ADS7128, CH7 is the LED (active low)
        // unordered map of channel to digital output value
        .digital_output_values = {{espp::Ads7138::Channel::CH7, 1}}, // start the LED off
        // enable oversampling / averaging
        .oversampling_ratio = espp::Ads7138::OversamplingRatio::OSR_32,
        .write = std::bind(&espp::I2c::write, &i2c, std::placeholders::_1, std::placeholders::_2,
                           std::placeholders::_3),
        .read = std::bind(&espp::I2c::read, &i2c, std::placeholders::_1, std::placeholders::_2,
                          std::placeholders::_3),
        .log_level = espp::Logger::Verbosity::WARN,
    });

    // create the gpio event queue
    gpio_evt_queue = xQueueCreate(10, sizeof(uint32_t));
    // setup gpio interrupts for mute button
    gpio_config_t io_conf;
    memset(&io_conf, 0, sizeof(io_conf));
    // interrupt on falling edge since the ALERT pin is pulled up
    io_conf.intr_type = GPIO_INTR_NEGEDGE;
    io_conf.pin_bit_mask = (1 << static_cast<int>(ALERT_PIN));
    io_conf.mode = GPIO_MODE_INPUT;
    io_conf.pull_up_en = GPIO_PULLUP_ENABLE; // it's pulled up on the BP-ADS7128 as well
    gpio_config(&io_conf);

    // install gpio isr service
    gpio_install_isr_service(0);
    gpio_isr_handler_add(ALERT_PIN, gpio_isr_handler, (void *)ALERT_PIN);

    // start the gpio task
    auto alert_task = espp::Task::make_unique({
        .callback = [&ads](auto &m, auto &cv) -> bool {
          static uint32_t io_num;
          // block until we get a message from the interrupt handler
          if (xQueueReceive(gpio_evt_queue, &io_num, portMAX_DELAY)) {
            // see if it's the mute button
            if (io_num == (int)ALERT_PIN) {
              // we got an interrupt from the ALERT pin, so read the event data
              uint8_t event_flags = 0;
              uint8_t event_high_flags = 0;
              uint8_t event_low_flags = 0;
              std::error_code ec;
              ads.get_event_data(&event_flags, &event_high_flags, &event_low_flags,
                                 ec); // NOTE: this clears the event flags / ALERT
              if (ec) {
                logger.error("error getting event data: {}", ec.message());
                return false;
              }

              // See if there was an alert on the digital input (Sel, channel 5)
              if (event_flags & select_bit_mask) {
                // See if there was actually a low event on the digital input (Sel, channel 5)
                if (event_low_flags & select_bit_mask) {
                  logger.info("ALERT: Select pressed!");
                }
              }
            }
          }
          // don't want to stop the task
          return false;
        },
        .task_config =
            {
                .name = "alert",
                .stack_size_bytes = 4 * 1024,
            },
    });
    alert_task->start();

    std::error_code ec;
    // configure the alert pin
    ads.configure_alert(espp::Ads7138::OutputMode::PUSH_PULL, espp::Ads7138::AlertLogic::ACTIVE_LOW,
                        ec);
    if (ec) {
      logger.error("error configuring alert: {}", ec.message());
    }

    // set the digital output drive mode to open-drain
    ads.set_digital_output_mode(espp::Ads7138::Channel::CH7, espp::Ads7138::OutputMode::OPEN_DRAIN,
                                ec);
    if (ec) {
      logger.error("error setting digital output mode: {}", ec.message());
    }

    // set an alert on the digital input (Sel) so that we can get notified when the button is
    // pressed (goes low)
    ads.set_digital_alert(espp::Ads7138::Channel::CH5, espp::Ads7138::DigitalEvent::LOW, ec);
    if (ec) {
      logger.error("error setting digital alert: {}", ec.message());
    }

    // make the task which will get the raw data from the I2C ADC
    fmt::print("%time (s), x (mV), y (mV), select pressed\n");
    auto ads_read_task_fn = [&ads](std::mutex &m, std::condition_variable &cv) {
      static auto start = std::chrono::high_resolution_clock::now();
      auto now = std::chrono::high_resolution_clock::now();
      auto elapsed = std::chrono::duration<float>(now - start).count();

      std::error_code ec;
      // get the analog input data
      auto all_mv = ads.get_all_mv(ec);
      if (ec) {
        logger.error("error getting analog data: {}", ec.message());
        return false;
      }
      auto x_mv = all_mv[0]; // the first channel is channel 1 (X axis)
      auto y_mv = all_mv[1]; // the second channel is channel 3 (Y axis)

      // alternatively we could get the analog data in a map
      auto mapped_mv = ads.get_all_mv_map(ec);
      if (ec) {
        logger.error("error getting analog data: {}", ec.message());
        return false;
      }

      x_mv = mapped_mv[espp::Ads7138::Channel::CH1];
      y_mv = mapped_mv[espp::Ads7138::Channel::CH3];

      // NOTE: we could get all digital inputs as a bitmask using
      // get_digital_input_values(), but we'll just get the one we want.
      // If we wanted to get all of them, we could do:
      // auto input_values = ads.get_digital_input_values();
      auto select_value = ads.get_digital_input_value(espp::Ads7138::Channel::CH5,
                                                      ec); // the button is on channel 5
      if (ec) {
        logger.error("error getting digital input value: {}", ec.message());
        return false;
      }

      auto select_pressed = select_value == 0; // joystick button is active low

      // use fmt to print so it doesn't have the prefix and can be used more
      // easily as CSV (for plotting using uart_serial_plotter)
      fmt::print("{:.3f}, {:.3f}, {:.3f}, {}\n", elapsed, x_mv, y_mv, select_pressed ? 1 : 0);
      if (select_pressed) {
        ads.set_digital_output_value(espp::Ads7138::Channel::CH7, 0, ec); // turn on the LED
      } else {
        ads.set_digital_output_value(espp::Ads7138::Channel::CH7, 1, ec); // turn off the LED
      }
      // NOTE: sleeping in this way allows the sleep to exit early when the
      // task is being stopped / destroyed
      {
        using namespace std::chrono_literals;
        std::unique_lock<std::mutex> lk(m);
        cv.wait_until(lk, now + 10ms);
      }
      // we don't want to stop, so return false
      return false;
    };

    auto ads_task = espp::Task::make_unique({.callback = ads_read_task_fn,
                                             .task_config =
                                                 {
                                                     .name = "ADS",
                                                     .stack_size_bytes{8 * 1024},
                                                 },
                                             .log_level = espp::Logger::Verbosity::INFO});
    ads_task->start();

Public Types

enum class OversamplingRatio : uint8_t

Possible oversampling ratios, see data sheet Table 15 (p. 34)

Values:

enumerator NONE

No oversampling.

enumerator OSR_2

2x oversampling

enumerator OSR_4

4x oversampling

enumerator OSR_8

8x oversampling

enumerator OSR_16

16x oversampling

enumerator OSR_32

32x oversampling

enumerator OSR_64

64x oversampling

enumerator OSR_128

128x oversampling

enum class Channel : uint8_t

Possible channel numbers.

The ADS7138 has 8 channels, see data sheet Table 1 (p. 4)

Note

The channel numbers are 0-indexed.

Note

The channel may be configured as digital input, digital output, or analog input.

Values:

enumerator CH0

Channel 0.

enumerator CH1

Channel 1.

enumerator CH2

Channel 2.

enumerator CH3

Channel 3.

enumerator CH4

Channel 4.

enumerator CH5

Channel 5.

enumerator CH6

Channel 6.

enumerator CH7

Channel 7.

enum class Mode : uint8_t

Possible modes for analog input conversion.

The ADS7128 device has the following sampling modes:

  • Manual Mode: Allows the external host processor to directly request and control when the data are sampled. The host provides I2C frames to control conversions and the captured data are returned overthe I2C bus after each conversion.

  • Auto-Sequence Mode: The host can configure the device to scan through the enabled analog input channels. The host must provide continuous clocks (SCL) to the device to scan through the channels and to read the data from the device. The mux automatically switches through the predetermined channel sequence, and the data conversion results are sent through the data bus.

  • Autonomous Mode: After receiving the first start of conversion pulse from the host, the ADS7128 device then generates the subsequent start of conversion signals autonomously. The device features an internal oscillator to generate the start of ADC conversion pulses without the host controlling the conversions. Output data are not returned over the digital bus; only a signal on the ALERT is generated when an input signal crosses the programmable thresholds.

Values:

enumerator MANUAL

Manual mode (9th falling edge of SCL (ACK) triggers conversion) and the MUX is controlled by register write to MANUAL_CHID field of the CHANNEL_SEL register.

enumerator AUTO_SEQ

Auto sequence mode (9th falling edge of SCL (ACK) triggers conversion) and the MUX is incremented after each conversion.

enumerator AUTONOMOUS

Autonomous mode (conversion is controlled by the ADC internally) and the MUX is incremented after each conversion.

enum class AnalogEvent

Event for triggering alerts on analog inputs.

Values:

enumerator OUTSIDE

Trigger when ADC value goes outside the low/high thresholds.

enumerator INSIDE

Trigger when ADC value goes inside the low/high thresholds.

enum class DigitalEvent

Event for triggering alerts on digital inputs.

Values:

enumerator HIGH

Trigger on logic 1.

enumerator LOW

Trigger on logic 0.

enum class OutputMode : uint8_t

Output mode for digital output channels and ALERT pin.

Values:

enumerator OPEN_DRAIN

Open drain output mode.

enumerator PUSH_PULL

Push-pull output mode.

enum class DataFormat : uint8_t

Enum for the data format that can be read from the ADC.

Values:

enumerator RAW

Raw data format, 12 bit ADC data.

enumerator AVERAGED

Averaged data format, 16 bit ADC data.

enum class Append : uint8_t

Enum for the different configurations of bits that can be appended to the data when reading from the ADC.

Values:

enumerator NONE

No append.

enumerator CHANNEL_ID

Append Channel ID.

enumerator STATUS

Append status flags.

enum class AlertLogic : uint8_t

Alert logic for ALERT pin.

Values:

enumerator ACTIVE_LOW

ALERT pin is active low.

enumerator ACTIVE_HIGH

ALERT pin is active high.

enumerator PULSED_LOW

ALERT pin is pulsed low per alert flag.

enumerator PULSED_HIGH

ALERT pin is pulsed high per alert flag.

typedef std::function<bool(uint8_t)> probe_fn

Function to probe the peripheral

Param address

The address to probe

Return

True if the peripheral is found at the given address

Public Functions

inline explicit Ads7138(const Config &config)

Construct Ads7138.

Parameters

config – Configuration structure.

inline void initialize(std::error_code &ec)

Initialize the ADC This function uses the configuration structure passed to the constructor to configure the ADC.

Note

This function must be called before any other functions as it configures the ADC pins and sets the mode.

Parameters

ec – Error code to set if an error occurs.

inline float get_mv(Channel channel, std::error_code &ec)

Communicate with the ADC to get the analog value for the channel and return it.

Note

The channel must have been configured as an analog input.

Note

If the ADC is in autonomous mode, this function will simply read the value from the ADC’s buffer. If the ADC is in manual mode, this function will trigger a conversion and then read the value from the ADC’s buffer (blocking until conversion is complete).

Note

This function will return 0 and log an error if the channel is not configured as an analog input.

Parameters
  • channel – Which channel of the ADC to read

  • ec – Error code to set if an error occurs.

Returns

The voltage (in mV) read from the channel.

inline std::vector<float> get_all_mv(std::error_code &ec)

Communicate with the ADC to get the analog value for all channels and return them.

Note

The channels must have been configured as analog inputs.

Note

The vector will be in the order of the channels configured in the constructor.

Note

The vector will be the same length as the number of channels configured in the constructor.

Note

If the ADC is in autonomous mode, this function will simply read the values from the ADC’s buffer. If the ADC is in manual mode, this function will trigger a conversion and then read the values from the ADC’s buffer (blocking until conversion is complete).

Parameters

ec – Error code to set if an error occurs.

Returns

A vector of the voltages (in mV) read from each channel.

inline std::unordered_map<Channel, float> get_all_mv_map(std::error_code &ec)

Communicate with the ADC to get the analog value for all channels and return them.

Note

These are the channels that were configured as analog inputs.

Note

If the ADC is in autonomous mode, this function will simply read the values from the ADC’s buffer. If the ADC is in manual mode, this function will trigger a conversion and then read the values from the ADC’s buffer (blocking until conversion is complete).

Parameters

ec – Error code to set if an error occurs.

Returns

An unordered map of the voltages (in mV) read from each channel.

inline void configure_alert(OutputMode output_mode, AlertLogic alert_logic, std::error_code &ec)

Configure the ALERT pin.

Parameters
  • output_mode – Output mode ALERT pin

  • alert_logic – Alert logic for ALERT pin

  • ec – Error code to set if an error occurs.

inline void set_analog_alert(Channel channel, float high_threshold_mv, float low_threshold_mv, AnalogEvent event, int event_count, std::error_code &ec)

Configure the analog channel to generate an alert when the voltage crosses a low or high threshold.

Note

The channel must have been configured as an analog input.

Parameters
  • channel – Analog channel to configure

  • high_threshold_mv – High threshold (in mV) to generate an alert

  • low_threshold_mv – Low threshold (in mV) to generate an alert

  • event – Event type which will generate an alert

  • event_count – Number of events to generate an alert (1-15). Checks n+1 consecutive samples above or below threshold before setting event flag.

  • ec – Error code to set if an error occurs.

inline void set_digital_alert(Channel channel, DigitalEvent event, std::error_code &ec)

Configure the digital input channel to generate an alert when the input goes high or low.

Parameters
  • channel – Digital input channel to configure

  • event – Event type which will generate an alert

  • ec – Error code to set if an error occurs.

inline void get_event_data(uint8_t *event_flags, uint8_t *event_high_flags, uint8_t *event_low_flags, std::error_code &ec)

Get all the event data registers.

Note

The event flags are cleared after reading.

Parameters
  • event_flags[inout] Event flag register

  • event_high_flags[inout] Event high flag register

  • event_low_flags[inout] Event low flag register

  • ec[inout] Error code to set if an error occurs.

inline uint8_t get_event_flags(std::error_code &ec)

Get the event flag register.

Note

The event flags are NOT cleared after reading.

Parameters

ec – Error code to set if an error occurs.

Returns

The event flag register

inline uint8_t get_event_high_flag(std::error_code &ec)

Get the event high flag register.

Note

The event high flags are NOT cleared after reading.

Parameters

ec – Error code to set if an error occurs.

Returns

The event high flag register

inline uint8_t get_event_low_flag(std::error_code &ec)

Get the event low flag register.

Note

The event low flags are NOT cleared after reading.

Parameters

ec – Error code to set if an error occurs.

Returns

The event low flag register

inline void clear_event_high_flag(uint8_t flags, std::error_code &ec)

Clear the event flag register.

Parameters
  • flags – Flags to clear

  • ec – Error code to set if an error occurs.

inline void clear_event_low_flag(uint8_t flags, std::error_code &ec)

Clear the event flag register.

Parameters
  • flags – Flags to clear

  • ec – Error code to set if an error occurs.

inline void set_digital_output_mode(Channel channel, OutputMode output_mode, std::error_code &ec)

Configure the digital output mode for the given channel.

Note

The channel must have been configured as a digital output.

Parameters
  • channel – Channel to configure

  • output_mode – Output mode for the channel

  • ec – Error code to set if an error occurs.

inline void set_digital_output_value(Channel channel, bool value, std::error_code &ec)

Set the digital output value for the given channel.

Note

The channel must have been configured as a digital output.

Parameters
  • channel – Which channel to set the digital output value for.

  • value – The value to set the digital output to.

  • ec – Error code to set if an error occurs.

inline bool get_digital_input_value(Channel channel, std::error_code &ec)

Get the digital input value for the given channel.

Note

The channel must have been configured as a digital input.

Parameters
  • channel – Which channel to get the digital input value for.

  • ec – Error code to set if an error occurs.

Returns

The value of the digital input.

inline uint8_t get_digital_input_values(std::error_code &ec)

Get the digital input values for all channels.

Note

The returned value is a bitfield, with each bit corresponding to a channel. The LSB corresponds to channel 0, the MSB to channel 7.

Note

Only channels configured as digital inputs are returned.

Parameters

ec – Error code to set if an error occurs.

Returns

The values of the digital inputs.

inline void reset(std::error_code &ec)

Perform a software reset of the device.

Note

This will reset all registers to their default values (converting all channels to analog inputs and disabling all events).

Note

If the write is successful, the function will wait for the reset to complete before returning

Parameters

ec – Error code to set if an error occurs.

inline bool probe (std::error_code &ec) requires(UseAddress)

Probe the peripheral

Note

This function is thread safe

Note

If the probe function is not set, this function will return false and set the error code to operation_not_supported

Note

This function is only available if UseAddress is true

Parameters

ec – The error code to set if there is an error

Returns

True if the peripheral is found

inline void set_address (uint8_t address) requires(UseAddress)

Set the address of the peripheral

Note

This function is thread safe

Note

This function is only available if UseAddress is true

Parameters

address – The address of the peripheral

inline void set_probe (const probe_fn &probe) requires(UseAddress)

Set the probe function

Note

This function is thread safe

Note

This should rarely be used, as the probe function is usually set in the constructor. If you need to change the probe function, consider using the set_config function instead.

Note

This function is only available if UseAddress is true

Parameters

probe – The probe function

inline void set_write(const write_fn &write)

Set the write function

Note

This function is thread safe

Note

This should rarely be used, as the write function is usually set in the constructor. If you need to change the write function, consider using the set_config function instead.

Parameters

write – The write function

inline void set_read(const read_fn &read)

Set the read function

Note

This function is thread safe

Note

This should rarely be used, as the read function is usually set in the constructor. If you need to change the read function, consider using the set_config function instead.

Parameters

read – The read function

inline void set_read_register(const read_register_fn &read_register)

Set the read register function

Note

This function is thread safe

Note

This should rarely be used, as the read register function is usually set in the constructor. If you need to change the read register function, consider using the set_config function instead.

Parameters

read_register – The read register function

inline void set_write_then_read(const write_then_read_fn &write_then_read)

Set the write then read function

Note

This function is thread safe

Note

This should rarely be used, as the write then read function is usually set in the constructor. If you need to change the write then

Parameters

write_then_read – The write then read function

inline void set_separate_write_then_read_delay(const std::chrono::milliseconds &delay)

Set the delay between the write and read operations in write_then_read

Note

This function is thread safe

Note

This should rarely be used, as the delay is usually set in the constructor. If you need to change the delay, consider using the set_config function instead.

Note

This delay is only used if the write_then_read function is not set to a custom function and the write and read functions are separate functions.

Parameters

delay – The delay between the write and read operations in write_then_read

inline void set_config(const Config &config)

Set the configuration for the peripheral

Note

This function is thread safe

Note

The configuration should normally be set in the constructor, but this function can be used to change the configuration after the peripheral has been created - for instance if the peripheral could be found on different communications buses.

Parameters

config – The configuration for the peripheral

inline void set_config(Config &&config)

Set the configuration for the peripheral

Note

This function is thread safe

Note

The configuration should normally be set in the constructor, but this function can be used to change the configuration after the peripheral has been created - for instance if the peripheral could be found on different communications buses.

Parameters

config – The configuration for the peripheral

inline const std::string &get_name() const

Get the name of the component

Note

This is the tag of the logger

Returns

A const reference to the name of the component

inline void set_log_tag(const std::string_view &tag)

Set the tag for the logger

Parameters

tag – The tag to use for the logger

inline espp::Logger::Verbosity get_log_level() const

Get the log level for the logger

Returns

The verbosity level of the logger

inline void set_log_level(espp::Logger::Verbosity level)

Set the log level for the logger

Parameters

level – The verbosity level to use for the logger

inline void set_log_verbosity(espp::Logger::Verbosity level)

Set the log verbosity for the logger

See also

set_log_level

Note

This is a convenience method that calls set_log_level

Parameters

level – The verbosity level to use for the logger

inline espp::Logger::Verbosity get_log_verbosity() const

Get the log verbosity for the logger

See also

get_log_level

Note

This is a convenience method that calls get_log_level

Returns

The verbosity level of the logger

inline void set_log_rate_limit(std::chrono::duration<float> rate_limit)

Set the rate limit for the logger

Note

Only calls to the logger that have _rate_limit suffix will be rate limited

Parameters

rate_limit – The rate limit to use for the logger

Public Static Attributes

static constexpr uint8_t DEFAULT_ADDRESS = (0x10)

Default I2C address of the device (when both R1 and R2 are DNP) (see data sheet Table 2, p. 16)

struct Config

Configuration structure.

Public Members

uint8_t device_address = DEFAULT_ADDRESS

I2C address of the device.

float avdd_volts = 3.3f

AVDD voltage in Volts. Used for calculating analog input voltage.

Mode mode = Mode::AUTONOMOUS

Mode for analog input conversion.

std::vector<Channel> analog_inputs = {}

List of analog input channels to sample.

std::vector<Channel> digital_inputs = {}

List of digital input channels to sample.

std::vector<Channel> digital_outputs = {}

List of digital output channels to sample.

std::unordered_map<Channel, OutputMode> digital_output_modes = {}

Optional output mode for digital output channels. If not specified, the default value is open-drain.

std::unordered_map<Channel, bool> digital_output_values = {}

Optional initial values for digital output channels. If not specified, the default value is false in open-drain mode.

OversamplingRatio oversampling_ratio = OversamplingRatio::NONE

Oversampling ratio to use.

bool statistics_enabled = true

Enable statistics collection (min, max, recent)

BasePeripheral::write_fn write

Function to write to the ADC.

BasePeripheral::read_fn read

Function to read from the ADC.

bool auto_init = true

Automatically initialize the ADC on construction. If false, initialize() must be called before any other functions.

espp::Logger::Verbosity log_level = {espp::Logger::Verbosity::WARN}

Verbosity for the logger.