nRF52840 high power consumption in Bluetooth / I2C application

Hi there, I've seen a couple of similar topics on this but none of them seem to exactly correspond to my issue. 

I'm working on a project that uses many different modules (bluetooth, GPIOTE, TWI, RTC, fstorage) here's the overview:

  • Implemented IR NEC receiver protocol to decode received commands and timestamps
  • Storing received commands and timestamps in an extended Bluetooth beacon
  • To minimize the power consumption there are a couple of measures in places:
    • There is an accelerometer (BMA220 implemented with the TWI module) to put the device to sleep after a certain period of no motion
    • There is a transistor acting as a switch to turn the IR receiver on/off after some time of inactivity
  • I'm using the flash storage to save the Bluetooth beacon information, because I'm using the deepest sleep mode (system off)

My main issue is the power consumption, even on the deepest sleep mode I can't get below 1.7 mA, this is a lot I know, I should be getting just a few uA.

I measured this value with an NRF power profiler, I'm using the nRF52840 dev kit, I'm using the "nrf only toggle" to turn off all the stuff that doesn't matter. The lowest I've got at a given time using the nrf52840 dongle was about 400uA but now it's around 800uA

I've tried forcing the TWI and GPIOTE modules to disable before entering sleep, I've also tried to increase the bluetooth adversting interval, but nothing seems to work, plus the sleep mode I'm using is a problem because it restarts the RTC so I should be using only the system on sleep mode, even in this mode the consumption should be way lower.


I am going to attach my main file so it's easier to get the overview.

Anyone has any idea on what I can try to reduce the consumption? Thanks in advance

#include <stdbool.h>
#include <stdint.h>
#include <stdio.h>
#include <math.h>
#include "nrf.h"
#include "nrf_soc.h"
#include "nordic_common.h"
#include "nrf_gpio.h"
#include "nrf_delay.h"
#include "nrf_drv_gpiote.h"
#include "nrf_drv_timer.h"
#include "nrf_drv_rtc.h"
#include "nrf_drv_clock.h"
#include "nrf_sdh.h"
#include "nrf_sdh_ble.h"
#include "nrf_fstorage_sd.h"
#include "nrf_fstorage.h"
#include "bsp.h"
#include "app_error.h"
#include "nrf_pwr_mgmt.h"

#include "app_timer.h"
#include "app_scheduler.h"
#include "nrf_soc.h"
#include "nrf_pwr_mgmt.h"

#include "nrf_log.h"
#include "nrf_log_ctrl.h"
#include "nrf_log_default_backends.h"

#include "application_code/ble_adv.h"
#include "application_code/ir_decode.h"
#include "application_code/bma220.h"

#define NON_CONNECTABLE_ADV_LED_PIN     BSP_BOARD_LED_0     //!< Toggles when non-connectable advertisement is sent.
#define CONNECTED_LED_PIN               BSP_BOARD_LED_1     //!< Is on when device has connected.
#define CONNECTABLE_ADV_LED_PIN         BSP_BOARD_LED_2     //!< Is on when device is advertising connectable advertisements.

#define TIMER_TICKS_TO_MS 0.01

#define BLINK_PERIOD (500 / TIMER_TICKS_TO_MS) // 500 ms
#define IR_COOLDOWN 1 // cooldown from another IR read in seconds
#define POWER_SAVING_TIME 120 // 5 min idle to enter power saving mode
#define IR_RX_OFF_TIME 30// 90s idle to turn off IR RX LED
#define RTC_FREQ        32768
#define RTC_PS  8

#define MAGIC_KEY_DEFAULT    0xFFAB0301

// Variable to store beacon info in the flash storage.
nrf_nvs_ble_t beacon_info;

const nrf_drv_rtc_t rtc = NRF_DRV_RTC_INSTANCE(2); /**< Declaring an instance of nrf_drv_rtc for RTC0. */

static void fstorage_evt_handler(nrf_fstorage_evt_t * p_evt);

NRF_FSTORAGE_DEF(nrf_fstorage_t fstorage) =
{
    /* Set a handler for fstorage events. */
    .evt_handler = fstorage_evt_handler,

    /* These below are the boundaries of the flash space assigned to this instance of fstorage.
     * You must set these manually, even at runtime, before nrf_fstorage_init() is called.
     * The function nrf5_flash_end_addr_get() can be used to retrieve the last address on the
     * last page of flash available to write data. */
    .start_addr = 0x3e000,
    .end_addr   = 0x3ffff,
};

static void fstorage_evt_handler(nrf_fstorage_evt_t * p_evt)
{
    if (p_evt->result != NRF_SUCCESS)
    {
        NRF_LOG_INFO("--> Event received: ERROR while executing an fstorage operation.");
        return;
    }

    switch (p_evt->id)
    {
        case NRF_FSTORAGE_EVT_WRITE_RESULT:
        {
            NRF_LOG_INFO("--> Event received: wrote %d bytes at address 0x%x.",
                         p_evt->len, p_evt->addr);
        } break;

        case NRF_FSTORAGE_EVT_ERASE_RESULT:
        {
            NRF_LOG_INFO("--> Event received: erased %d page from address 0x%x.",
                         p_evt->len, p_evt->addr);
        } break;

        default:
            break;
    }
}

/**@brief Function for initializing power management.
 */
static void power_management_init(void)
{
    ret_code_t err_code;
    err_code = nrf_pwr_mgmt_init();
    APP_ERROR_CHECK(err_code);
}

/**@brief Function for handling the idle state (main loop).
 *
 * @details If there is no pending log operation, then sleep until next the next event occurs.
 */
static void idle_state_handle(void)
{
    app_sched_execute();
    nrf_pwr_mgmt_run();
}

static void timers_init(void)
{
    ret_code_t err_code = app_timer_init();
    APP_ERROR_CHECK(err_code);
}

/**@brief Function for initializing the nrf log module.
 */
static void log_init(void)
{
    ret_code_t err_code = NRF_LOG_INIT(NULL);
    APP_ERROR_CHECK(err_code);

    NRF_LOG_DEFAULT_BACKENDS_INIT();
}

/** @brief: Function for handling the RTC0 interrupts.
 * Triggered on TICK and COMPARE0 match.
 */
static void rtc_handler(nrf_drv_rtc_int_type_t int_type)
{
    //DO NOTHING AT ALL
}

static void rtc_config(void)
{
    uint32_t err_code;

    //Initialize RTC instance
    nrf_drv_rtc_config_t config = NRF_DRV_RTC_DEFAULT_CONFIG;
    config.prescaler = 255;
    err_code = nrf_drv_rtc_init(&rtc, &config, rtc_handler);
    APP_ERROR_CHECK(err_code);

    //Power on RTC instance
    nrf_drv_rtc_enable(&rtc);
}

void wait_for_flash_ready(nrf_fstorage_t const * p_fstorage)
{
    /* While fstorage is busy, sleep and wait for an event. */
    while (nrf_fstorage_is_busy(p_fstorage))
    {
        nrf_pwr_mgmt_run();
    }
}

/**
 * @brief Function for main application entry.
 */
int main(void)
{
    uint32_t err_code = NRF_SUCCESS;
    // Define start position for namespace id.
    uint8_t namespace_id = 0;
    //uint8_t *p_ns_id = (uint8_t *)namespace_id;
    // Init timestamp variable
    uint16_t timestamp = 0;
    // Init variable for the last saved timestamp
    uint16_t last_command_timestamp = 0;
    uint8_t last_command = 0;
    // Init variable for saving the start time for led blinking
    uint32_t start_time = 0;
    // Init variable for error expire period
    uint32_t error_expire_period = 0;
    // Init variable for led state
    uint8_t led_state = 1;
    // General use elapsed
    uint32_t elapsed = 0;

    // Accellerometer variables
    uint8_t buf = 0;
    bool movement = false;
    uint32_t last_activity_count = 0;

    // Pointer for the NVS Storage Soft Device api
    nrf_fstorage_api_t * p_fs_api;

    /* Initialize logging system and GPIOs. */
    log_init();
    timers_init();
    // Configure all leds on board.
    bsp_board_init(BSP_INIT_LEDS);

    // Initialize.
    power_management_init();
    // Initialize BLE module
    ble_stack_init();
    advertising_init();

    /* Initialize an fstorage instance using the nrf_fstorage_nvmc backend.
     * nrf_fstorage_nvmc uses the NVMC peripheral. This implementation can be used when the
     * SoftDevice is disabled or not present.
     *
     * Using this implementation when the SoftDevice is enabled results in a hardfault. */
    p_fs_api = &nrf_fstorage_sd;
    NRF_LOG_INFO("Initializing nrf_fstorage_nvmc implementation...");
    err_code = nrf_fstorage_init(&fstorage, p_fs_api, NULL);
    APP_ERROR_CHECK(err_code);
    NRF_LOG_PROCESS();

    // Start BLE advertising
    advertising_start();
    // Start execution.
    NRF_LOG_INFO("IR BEACON STARTED - with TWI disable");
    NRF_LOG_PROCESS();
    // Configure RTC for counting timestamp
    rtc_config();
    
    // set p0.15 as output
    nrf_gpio_cfg_output(OUTPUT_PIN);
    // Set IR_SWITCH as output to turn on/off the IR receiver LED.
    nrf_gpio_cfg_output(IR_SWITCH);
    // Configure BMA220 INT PIN as wake up from System off mode.
    nrf_gpio_cfg_sense_input(INT_PIN, NRF_GPIO_PIN_PULLUP, NRF_GPIO_PIN_SENSE_HIGH);

    // config int pin
    gpio_interrupt_init();
    // timer led init
    timer_led_init();

    // start with the led on
    bsp_board_led_on(0);

    // Initiate I2C communication
    twi_init();
    
    // BM220 initial configs 
    // 2G range
    bma220_register_write(0x22, 0x00);
    // 32Hz low pass filter
    bma220_register_write(0x20, 0x05);
    // enable orientation detection for INT pin (enabled axis slope detection as well - seems to trigger more reliably)
    bma220_register_write(0x1A, 0x78);
    // enable low power mode with 2s sleep duration, xyz axis enabled
    bma220_register_write(0x1E, 0x6F);
    bma220_register_read(0x1C, &buf, 1);
    bma220_register_write(0x1C, (buf & 0b10001111) | (0x4 << 4));

    // Start by reading the beacon storage stored in the flash memory.
    nrf_fstorage_read(&fstorage, 0x0003e000, &beacon_info, sizeof(beacon_info));
    /* While fstorage is busy, sleep and wait for an event. */
    wait_for_flash_ready(&fstorage);

    // Check if this is a new device with no previous data.
    if (beacon_info.magic_key != MAGIC_KEY_DEFAULT) {
        NRF_LOG_INFO("MAGIC KEY INVALID");
        // Set the key so this condition doesn't repeat in the next bootup
        beacon_info.magic_key = MAGIC_KEY_DEFAULT;

        // Initialize the flash structure with the beacon info. 
        memcpy(beacon_info.ble_payload, m_beacon_info, sizeof(beacon_info.ble_payload));
        memcpy(beacon_info.struct_align, m_beacon_info, sizeof(beacon_info.struct_align));
        beacon_info.ns_id = 0;

        // Write the initialization to the flash storage.
        nrf_fstorage_erase(&fstorage, 0x0003e000, 1, NULL);
        nrf_fstorage_write(&fstorage, 0x0003e000, &beacon_info,sizeof(beacon_info), NULL);
        wait_for_flash_ready(&fstorage);
    }

    NRF_LOG_INFO("BEACON: ");
    NRF_LOG_HEXDUMP_INFO(beacon_info.ble_payload, sizeof(beacon_info.ble_payload));
    NRF_LOG_INFO("NS ID: %d",beacon_info.ns_id);
    NRF_LOG_PROCESS();

    // Copy payload and namespace id available in the NVS storage to the BLE adv data.
    memcpy(m_beacon_info, beacon_info.ble_payload, sizeof(beacon_info.ble_payload) > sizeof(m_beacon_info) ? sizeof(m_beacon_info) : sizeof(beacon_info.ble_payload));
    namespace_id = beacon_info.ns_id;

    // Set BLE adv data for the first time since flash has been read.
    ble_advdata_set(0,0,0,true);

    while (1)
    {
        idle_state_handle();

        // Get timestamp and convert to seconds.
        //timestamp = nrf_drv_rtc_counter_get(&rtc) / 32768 ;
        timestamp = nrf_drv_rtc_counter_get(&rtc) / (RTC_FREQ / (1 << RTC_PS)) ;
        
        // // Read Accel axis data
        // if (!bma220_register_read(0x04, &x, 8) || !bma220_register_read(0x06, &y, 8) || !bma220_register_read(0x08, &z, 8)) {

        //     NRF_LOG_INFO("Failed reading accelerometer data");
        //     NRF_LOG_PROCESS();

        // }
        
        // // Calculate resulting vector
        // vector = sqrt(pow(x,2) + pow(y,2) + pow(z,2));
        // //NRF_LOG_INFO("ACCEL VECTOR: x: %d | y: %d | z: %d | ABS: %d", x, y, z, vector);
        // NRF_LOG_PROCESS();

        // NRF_LOG_INFO("X: %u | Y: %u | Z: %u | vector: %u", x, y, z, vector);
        // NRF_LOG_PROCESS();
 
        // If movement is detected
        NRF_LOG_PROCESS();
        // if (abs(prev_vector - vector) > 10 && movement == false) {
        if (nrf_gpio_pin_read(INT_PIN) && movement == false) {
            NRF_LOG_INFO("Movement detected");
            //prev_vector = vector;
            movement = true;
            last_activity_count = timestamp;
            NRF_LOG_INFO("Turning ON IR!");
            NRF_LOG_PROCESS();
            
            nrf_gpio_pin_set(IR_SWITCH);
        }
        // else if (abs(prev_vector - vector) < 100 && movement == true){
        else if (!nrf_gpio_pin_read(INT_PIN) && movement == true){
            movement = false;
            //prev_vector = vector;
            NRF_LOG_INFO("Movement stopped");
        }
        
        nrf_gpio_pin_set(IR_SWITCH);


        if ((_led_counter - start_time) >= BLINK_PERIOD)
        {
            // update the timer
            start_time = _led_counter;

            // blink the led
            if (led_state)
            {
                bsp_board_led_on(0);
                // nrf_gpio_pin_write(OUTPUT_PIN, state);
            }
            else
            {
                bsp_board_led_off(0);
                // nrf_gpio_pin_write(OUTPUT_PIN, state);
            }

            led_state = !led_state;
        }

        if (error_expire_period && (_led_counter > error_expire_period) ) {
            error_expire_period = 0;
            bsp_board_led_off(1);
        }

        // max 100ms for IR frame
        if ( nec_state != 0 && _timer_counter > 10000) {
            nec_state = 0;
            bsp_board_led_on(1);
            error_expire_period = _led_counter + 500000;
        }

        // If a valid IR command has been received start save it to the BLE beacon.
        if (nec_ok) {
            nec_ok = 0;
            nec_state = 0;
            
            // Set command and timestamp by reversing the received bits.
            //uint16_t le_address = nec_code >> 24;
            //uint8_t address = reverseBits((uint8_t)le_address);
            uint8_t le_cmd = nec_code >> 8;
            //uint8_t inv_command = nec_code;
            uint8_t command = reverseBits(le_cmd);
            // Debug purposes
            // NRF_LOG_INFO("ADDR: %02X, LE_CMD: %02X, ICMD: %02X, CMD: %02X",address,le_cmd,inv_command,command);
            // NRF_LOG_PROCESS();

            if (timestamp < last_command_timestamp) {
                // Max rtc value with prescaler = 8 -> 131072 (limited to 65536 (2 bytes))
                elapsed = (65536 - last_activity_count) + timestamp;
            } else {
                elapsed = timestamp - last_activity_count;
            }
            
            // Only set the new data in beacon if namespace is within length and at least IR_COOLDOWN seconds have passed
            if ((last_command != command) || ((last_command == command) && (elapsed > IR_COOLDOWN)) ) {
                // Set new data on the beacon.
                ble_advdata_set(command, timestamp, namespace_id, false);

                // Debug purposes
                NRF_LOG_INFO("CMD: %02X | CNT: %u | TS: %u | NAMESPACE: %d | ERROR: %u", command, _led_counter/100000, timestamp, namespace_id, err_code);
                NRF_LOG_PROCESS();
                // Increase index (1 byte for cmd, 2 for ts).
                namespace_id = (namespace_id + 3) % APP_ADV_DATA_LENGTH;
                last_activity_count = timestamp;
            }
            
            // update last_command 
            last_command = command;

            // Update last_timestamp.
            last_command_timestamp = timestamp;

            // receive again!
            nrf_drv_gpiote_in_event_enable(PIN_IN, true);
        }
        
        /////////////////////// POWER SAVING MODE TEST ///////////////////////////
        if (timestamp < last_activity_count) {
            // Max rtc value with prescaler = 8 -> 131072 (limited to 65536 (2 bytes))
            elapsed = (65536 - last_activity_count) + timestamp;
        } else {
            elapsed = timestamp - last_activity_count;
        }

        if ( elapsed > POWER_SAVING_TIME){
           
            NRF_LOG_INFO("Entering low power mode!");
            NRF_LOG_INFO("Writing to flash.");
            
            // Disable TWI module.
            twi_disable();
            nrf_drv_gpiote_uninit();
            nrf_delay_ms(1000);

            // Copy beacon info to flash variables
            memcpy(beacon_info.ble_payload, m_beacon_info, sizeof(beacon_info.ble_payload));
            memcpy(&beacon_info.ns_id, &namespace_id, sizeof(beacon_info.ns_id));
            NRF_LOG_PROCESS();

            nrf_fstorage_erase(&fstorage, 0x0003e000, 1, NULL);
            wait_for_flash_ready(&fstorage);
            err_code = nrf_fstorage_write(&fstorage, 0x0003e000, &beacon_info, sizeof(beacon_info), NULL);
            APP_ERROR_CHECK(err_code);
            NRF_LOG_PROCESS();
            /* While fstorage is busy, sleep and wait for an event. */
            wait_for_flash_ready(&fstorage);

            NRF_LOG_INFO("Done.");
            NRF_LOG_PROCESS();

            // Make sure it's stable before shutdown.
            nrf_delay_ms(1000);
            nrf_pwr_mgmt_shutdown(NRF_PWR_MGMT_SHUTDOWN_GOTO_SYSOFF);
        }
        // Turn of IR RX LED after 30s iddle.
        else if (elapsed > IR_RX_OFF_TIME) {
            // NRF_LOG_INFO("Turning Off IR!");
            // NRF_LOG_PROCESS();
            nrf_gpio_pin_clear(IR_SWITCH);
        }
    }
}
/** @} */

Parents Reply Children
Related