SAADC sampling causes periodic/repeated failure with I2C communication stream

System Details:

  • Board: Custom
  • Chip: nRF52840/nRF52833
  • PCA Number: PCA10056/10100
  • SoftDevice: S140, v7
  • nRF5 SDK: Version 16.0.0
  • mdk version: 8.46.0
  • nrfjprog version: 10.15.4 external
  • JLinkARM.dll version: 7.64d

Hello,

I have a BLE UART app that streams on-board sensor data to my central BLE device (laptop) every 50ms (20hz). I visualize this incoming data continuously, and I noticed that every 5 seconds, there is an I2C/TWI communication failure and all sensor data momentarily goes to 0s as the I2C lines become unavailable.

I was able to confirm that this periodic error comes from my code that performs SAADC sampling to read the on-board battery level. When I disabled this SAADC module, the error goes away completely. For context, my code uses a timer, which triggers the SAADC sampling by calling nrf_drv_saadc_sample(). This timer is triggered every BATTERY_SAMPLE_PERIOD milliseconds. I began experimenting with this timer frequency, and I noticed that if this timer is triggered every 900ms (or longer), then the I2C communication error will arise. However, if I set this BATTERY_SAMPLE_PERIOD to something shorter than that, say 800, then this issue never occurs. However, the end result is never actually calculated in only 700ms...generally takes a couple seconds.

Ideally, we want to be able to sample this battery level every 20 seconds or something, but it seems this communication error arises anytime we set the value above 900. My hunch makes me feel like this issue comes about when the SAADC module finishes sampling & sends an interrupt to the main program thread, which blocks the i2c/twi communication somehow. Is there some explanation for this behavior? Would you recommend a way to deal with these types of SAADC timing-related issues?

Here is my battery.c file which contains the battery sampling code for your reference:

#include "app_error.h"
#include "app_scheduler.h"
#include "app_timer.h"
#include "battery.h"
#include "board.h"
#include "nrf_drv_saadc.h"
#include "nrf_log.h"
#include "nrf_gpio.h"

#define BATTERY_SAMPLE_PERIOD                   700

#define SAADC_BUFFER_SIZE                       3

#define ADC_VOLTAGE_DIV_COMPENSATION            2 // 10M / (10M + 10M)
#define ADC_REF_VOLTAGE_IN_MILLIVOLTS           600
#define ADC_PRE_SCALING_COMPENSATION            6
#define ADC_RESULT_IN_MILLI_VOLTS(ADC_VALUE)    ((((ADC_VALUE) * ADC_REF_VOLTAGE_IN_MILLIVOLTS) / 1023) * ADC_PRE_SCALING_COMPENSATION * ADC_VOLTAGE_DIV_COMPENSATION)

APP_TIMER_DEF(m_batteryTimerId);

static nrf_saadc_value_t m_buffer_pool[2][SAADC_BUFFER_SIZE];
static uint16_t m_vBat;

void saadc_callback(nrf_drv_saadc_evt_t const * p_event)
{
    ret_code_t err_code;
    uint16_t adc_sum_value = 0;
    uint16_t adc_average_value;
    uint16_t adc_result_millivolts;

    if (p_event->type == NRF_DRV_SAADC_EVT_DONE)
    {
        int i;
        for (i = 0; i < SAADC_BUFFER_SIZE; i++)
        {
            adc_sum_value += p_event->data.done.p_buffer[i];
        }
        adc_average_value = adc_sum_value / p_event->data.done.size;
        //NRF_LOG_INFO("[battery] ADC avg value: %d \r\n", adc_average_value);
				
        adc_result_millivolts = ADC_RESULT_IN_MILLI_VOLTS(adc_average_value);
        m_vBat = adc_result_millivolts;

        NRF_LOG_INFO("[battery] ADC result: %dmV\r\n", adc_result_millivolts);

        err_code = nrf_drv_saadc_buffer_convert(p_event->data.done.p_buffer, SAADC_BUFFER_SIZE);
        APP_ERROR_CHECK(err_code);
    }
}

static void vBatSampleHelper(void)
{
    // Trigger sampling
    ret_code_t ret = nrf_drv_saadc_sample();
    APP_ERROR_CHECK(ret);
}

uint16_t batteryGetVbat(void)
{
    return m_vBat;
}

void batteryTimerHandler(void * p_context)
{
    app_sched_event_put(NULL, 0, (app_sched_event_handler_t)vBatSampleHelper);
}

void batterySamplingStart(void)
{
    // Start timer
    uint32_t ret = app_timer_start(m_batteryTimerId, APP_TIMER_TICKS(BATTERY_SAMPLE_PERIOD), NULL);
    APP_ERROR_CHECK(ret);

#ifdef NRF52832_XXAA
    // Initialize SAADC hardware to produce correct VBAT readings
    nrf_gpio_pin_set(PIN_VBAT_EN);
#endif
}

void batterySamplingStop(void)
{
    app_timer_stop(m_batteryTimerId);
#ifdef NRF52832_XXAA
    nrf_gpio_pin_clear(PIN_VBAT_EN);
#endif
}

void batteryInit(void)
{
    ret_code_t ret;

#ifdef NRF52832_XXAA
    /* Configure PIN_VBAT_EN as an OUTPUT */
    nrf_gpio_cfg_output(PIN_VBAT_EN);
    /* Write PIN_VBAT_EN to a LOW value (disables SAADC VBAT Reading Voltage Divider until BLE connects) */
    nrf_gpio_pin_clear(PIN_VBAT_EN);
#endif

    // Configure SAADC   
    nrf_saadc_channel_config_t channel_config = NRF_DRV_SAADC_DEFAULT_CHANNEL_CONFIG_SE(PIN_VBAT_SENSE);  // SELECT CHANNEL
    channel_config.reference = NRF_SAADC_REFERENCE_INTERNAL; // _REFERENCE_VDD4;
    channel_config.gain = NRF_SAADC_GAIN1_6; // _GAAIN1_4;

    ret = nrf_drv_saadc_init(NULL, saadc_callback);
    APP_ERROR_CHECK(ret);
    ret = nrf_drv_saadc_channel_init(0, &channel_config);
    APP_ERROR_CHECK(ret);
    ret = nrf_drv_saadc_buffer_convert(m_buffer_pool[0], SAADC_BUFFER_SIZE);
    APP_ERROR_CHECK(ret);
    ret = nrf_drv_saadc_buffer_convert(m_buffer_pool[1], SAADC_BUFFER_SIZE);
    APP_ERROR_CHECK(ret);

    // Create timer for periodic battery sampling
    ret = app_timer_create(&m_batteryTimerId, APP_TIMER_MODE_REPEATED, batteryTimerHandler);
    APP_ERROR_CHECK(ret);
}

Many thanks in advance,

Corten

  • Here is the code from that API call, with several related function definitions (most notably the very last function definition):

    /*!
     * @brief This API gets the sensor/feature data for accelerometer, gyroscope,
     * auxiliary sensor, step counter, high-g, gyroscope user-gain update,
     * orientation, gyroscope cross sensitivity and error status for NVM and VFRM.
     */
    int8_t bmi2_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev)
    {
        /* Variable to define error */
        int8_t rslt;
    
        /* Variable to define loop */
        uint8_t loop;
    
        /* Variable to get the status of advance power save */
        uint8_t aps_stat = 0;
    
        /* Null-pointer check */
        rslt = null_ptr_check(dev);
        if ((rslt == BMI2_OK) && (sensor_data != NULL))
        {
            /* Get status of advance power save mode */
            aps_stat = dev->aps_status;
            for (loop = 0; loop < n_sens; loop++)
            {
                /* Disable Advance power save if enabled for feature
                 * configurations
                 */
                if (sensor_data[loop].type >= BMI2_MAIN_SENS_MAX_NUM)
                {
                    if (aps_stat == BMI2_ENABLE)
                    {
                        /* Disable advance power save if
                         * enabled
                         */
                        rslt = bmi2_set_adv_power_save(BMI2_DISABLE, dev);
                    }
                }
                if (rslt == BMI2_OK)
                {
                    switch (sensor_data[loop].type)
                    {
                        case BMI2_ACCEL:
    
                            /* Get accelerometer data */
                            rslt = get_accel_sensor_data(&sensor_data[loop].sens_data.acc, BMI2_ACC_X_LSB_ADDR, dev);
                            break;
                        case BMI2_GYRO:
    
                            /* Get gyroscope data */
                            rslt = get_gyro_sensor_data(&sensor_data[loop].sens_data.gyr, BMI2_GYR_X_LSB_ADDR, dev);
                            break;
                        case BMI2_AUX:
    
                            /* Get auxiliary sensor data in data mode */
                            rslt = read_aux_data_mode(sensor_data[loop].sens_data.aux_data, dev);
                            break;
                        default:
                            rslt = BMI2_E_INVALID_SENSOR;
                            break;
                    }
    
                    /* Return error if any of the get sensor data fails */
                    if (rslt != BMI2_OK)
                    {
                        break;
                    }
                }
    
                /* Enable Advance power save if disabled while
                 * configuring and not when already disabled
                 */
                if ((aps_stat == BMI2_ENABLE) && (rslt == BMI2_OK))
                {
                    rslt = bmi2_set_adv_power_save(BMI2_ENABLE, dev);
                }
            }
        }
        else
        {
            rslt = BMI2_E_NULL_PTR;
        }
    
        return rslt;
    }
    
    
    
    
    /*!
     * @brief This internal API gets the accelerometer data from the register.
     */
    static int8_t get_accel_sensor_data(struct bmi2_sens_axes_data *data, uint8_t reg_addr, const struct bmi2_dev *dev)
    {
        /* Variable to define error */
        int8_t rslt;
    
        /* Array to define data stored in register */
        uint8_t reg_data[BMI2_ACC_GYR_NUM_BYTES] = { 0 };
    
        /* Read the sensor data */
        rslt = bmi2_get_regs(reg_addr, reg_data, BMI2_ACC_GYR_NUM_BYTES, dev);
        if (rslt == BMI2_OK)
        {
            /* Get accelerometer data from the register */
            get_acc_gyr_data(data, reg_data);
    
            /* Get the re-mapped accelerometer data */
            get_remapped_data(data, dev);
        }
    
        return rslt;
    }
    
    
    /*!
     * @brief This internal API gets the gyroscope data from the register.
     */
    static int8_t get_gyro_sensor_data(struct bmi2_sens_axes_data *data, uint8_t reg_addr, const struct bmi2_dev *dev)
    {
        /* Variable to define error */
        int8_t rslt;
    
        /* Array to define data stored in register */
        uint8_t reg_data[BMI2_ACC_GYR_NUM_BYTES] = { 0 };
    
        /* Read the sensor data */
        rslt = bmi2_get_regs(reg_addr, reg_data, BMI2_ACC_GYR_NUM_BYTES, dev);
        if (rslt == BMI2_OK)
        {
            /* Get gyroscope data from the register */
            get_acc_gyr_data(data, reg_data);
    
            /* Get the compensated gyroscope data */
            comp_gyro_cross_axis_sensitivity(data, dev);
    
            /* Get the re-mapped gyroscope data */
            get_remapped_data(data, dev);
    
        }
    
        return rslt;
    }
    
    
    /*!
     * @brief This internal API gets the accelerometer/gyroscope data.
     */
    static void get_acc_gyr_data(struct bmi2_sens_axes_data *data, const uint8_t *reg_data)
    {
        /* Variables to store msb value */
        uint8_t msb;
    
        /* Variables to store lsb value */
        uint8_t lsb;
    
        /* Variables to store both msb and lsb value */
        uint16_t msb_lsb;
    
        /* Variables to define index */
        uint8_t index = 0;
    
        /* Read x-axis data */
        lsb = reg_data[index++];
        msb = reg_data[index++];
        msb_lsb = ((uint16_t) msb << 8) | (uint16_t) lsb;
        data->x = (int16_t) msb_lsb;
    
        /* Read y-axis data */
        lsb = reg_data[index++];
        msb = reg_data[index++];
        msb_lsb = ((uint16_t) msb << 8) | (uint16_t) lsb;
        data->y = (int16_t) msb_lsb;
    
        /* Read z-axis data */
        lsb = reg_data[index++];
        msb = reg_data[index++];
        msb_lsb = ((uint16_t) msb << 8) | (uint16_t) lsb;
        data->z = (int16_t) msb_lsb;
    }
    
    
    /*!
     * @brief This API reads the data from the given register address of bmi2
     * sensor.
     *
     * @note For most of the registers auto address increment applies, with the
     * exception of a few special registers, which trap the address. For e.g.,
     * Register address - 0x26, 0x5E.
     */
    int8_t bmi2_get_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi2_dev *dev)
    {
        /* Variable to define error */
        int8_t rslt;
    
        /* Variable to define temporary length */
        uint16_t temp_len = len + dev->dummy_byte;
    
        /* Variable to define temporary buffer */
        uint8_t temp_buf[temp_len];
    
        /* Variable to define loop */
        uint16_t index = 0;
    
        /* Null-pointer check */
        rslt = null_ptr_check(dev);
        if ((rslt == BMI2_OK) && (data != NULL))
        {
            /* Configuring reg_addr for SPI Interface */
            if (dev->intf == BMI2_SPI_INTERFACE)
            {
                reg_addr = (reg_addr | BMI2_SPI_RD_MASK);
            }
            if (dev->aps_status == BMI2_ENABLE)
            {
                rslt = dev->read(dev->dev_id, reg_addr, temp_buf, temp_len);
                dev->delay_us(450);
            }
            else
            {
                rslt = dev->read(dev->dev_id, reg_addr, temp_buf, temp_len);
                dev->delay_us(20);
            }
    
            if (rslt == BMI2_OK)
            {
                /* Read the data from the position next to dummy byte */
                while (index < len)
                {
                    data[index] = temp_buf[index + dev->dummy_byte];
                    index++;
                }
            }
            else
            {
                rslt = BMI2_E_COM_FAIL;
            }
        }
        else
        {
            rslt = BMI2_E_NULL_PTR;
        }
    
        return rslt;
    }

    As you can see in the last function definition, bmi2_get_regs() is the function at the root of this API call which actually performs the Register Read operation to extract the IMU data (3-axes of data for both the accelerometer + gyroscope). You can also see in this function the BMI2_E_COM_FAIL which occurs as a result of a non-zero return value from performing dev->read(), which is defined in the imuInit() function, which I am attaching here for your reference:

    void imuInit(imuInstance_t instance)
    {
        int8_t rslt;
        struct bmi2_dev * p_dev;
    
        if (instance == IMU_PRIMARY)
        {
            p_dev = &m_imuPrimary;
            p_dev->dev_id = BMI2_I2C_PRIM_ADDR;
        }
        else if (instance == IMU_SECONDARY)
        {
            p_dev = &m_imuSecondary;
            p_dev->dev_id = BMI2_I2C_SEC_ADDR;
        }
    
        p_dev->read = imuRegRead;
        p_dev->write = imuRegWrite;
        p_dev->delay_us = delay_us;
        p_dev->read_write_len = 128;
        p_dev->intf = BMI2_I2C_INTERFACE;
        p_dev->config_file_ptr = NULL;
    
        uint8_t buff[1] = {0};
        if (instance == IMU_PRIMARY)
        {
            imuRegRead(BMI270_PRIM_ADDR, BMI270_ID_ADDR, &buff[0], 1);
            NRF_LOG_INFO("BMI270 Primary Chip ID: 0x%x", buff[0]);
        }
        else if (instance == IMU_SECONDARY)
        {
            imuRegRead(BMI270_SEC_ADDR, BMI270_ID_ADDR, &buff[0], 1);
            NRF_LOG_INFO("BMI270 Secondary Chip ID: 0x%x", buff[0]);
        }
    
        rslt = bmi270_init(p_dev);
        imuPrintRslt(rslt);
    
        imuEnable(instance);
    }
    
    
    static int8_t imuRegRead(uint8_t dev_addr, uint8_t reg_addr, uint8_t * data, uint16_t len)
    {
        uint32_t ret = twiRegRead(dev_addr, reg_addr, data, len);
        if (ret != NRF_SUCCESS)
        {
            return BMI2_E_COM_FAIL;
        }
    
        return BMI2_OK;
    }
    
    
    uint32_t twiRegRead(uint8_t slaveAddr, uint8_t regAddr, uint8_t * pdata, uint16_t length)
    {
        uint32_t ret;
    
        nrf_drv_twi_xfer_desc_t xfer = NRF_DRV_TWI_XFER_DESC_TXRX(slaveAddr, &regAddr, 1, pdata, length);
        m_xfer_status = 0;
    
        ret = nrf_drv_twi_xfer(&m_twi, &xfer, 0);
    
    
        if (NRF_SUCCESS != ret)
        {
            return ret;
        }
    
        // Wait for response for 5 ms
        for(uint32_t k = 0; k <= 5000; k++)
        {
            if(m_xfer_status != 0)
            {
                nrf_delay_ms(1);
                break;
            }
            nrf_delay_us(1);
        }
    
        if(m_xfer_status == TWI_XFER_STATUS_SUCCESS)
        {
            return NRF_SUCCESS;
        }
        else
        {
            return NRF_ERROR_INTERNAL;
        }
    }

    To be sure, this communication error is clearly happening across more than just this IMU sensor. I see this all-zero glitch occur in our Barometer data stream as well, and sometimes with our capacitive touch sensor (although less common for all cap touch values to go to zero for some reason). I am only going a bit deeper on this IMU case because it has a nice API to reference here in this discussion.

  • Ok, so what I can see from this is that rslt = BMI2_OK, meaning that both "dev" and "data" are non-null pointers.

    Then you read the same register, but the delay depends on dev->aps_status. What is dev->aps_status in the case where it fails?

    And regardless of what dev->read() returns, as long as it is not BMI2_OK, you will return BMI_E_COM_FAIL. Did you check what dev->read() returns in the failing case? That is, BMI2_E_COM_FAIL will be returned by the imuRegRead as long as twiRegRead() doesn't return NRF_SUCCESS. But what does twiRegRead return when it doesn't return NRF_SUCCESS? 

Related