Getting lower power consumption on Seeed XIAO nRF52840

I have a XIAO nRF52840 device that I am currently trying to get to its lowest power consumption possible when in deep sleep. I am currently turning off the SPI Flash prior to going into deep sleep and have uploaded the bootloader “update-Seeed_XIAO_nRF52840_Sense_bootloader-0.6.1_nosd.uf2” to the device which from other forums have stated that it is needed for lower power consumption. I am still getting the power consumption at 670 microamps while I am trying to get it down to at least 5-7 microamps. Any advice on how I can get lower power consumption on this device? Below is some code snippets attached of turning off the SPI Flash and entering low power mode. I do also have a BLE beacon service running. Could this be preventing the device from reaching its lowest power consumption?

Turning off SPI Flash:

1 Like

Had to put the other screenshot as a separate post because this forum doesn’t allow new users to attach two files for some reason.

Entering Deep Sleep:

I found good hints on this topic page XIAO BLE Sense in deep sleep mode. But many of the code snippets I saw in the thread were not working as I expected. I dug into the arduino core try to understand the underlying implementation. Based on my digging, I developed the below sketch. The arduino loop runs at 3uA (with a major caveat). It demonstrates system_off sleep with wake up on gpio interrupt, system_on sleep, and a low latency Arduino main loop. More info on my findings below the sketch. (I tried to post this on the other topic, but the post is stuck in a “pending” state.)

#include "Adafruit_SPIFlash.h"

#define DO_WORK_PIN   D3
#define SHUTDOWN_PIN  D4

Adafruit_FlashTransport_QSPI flashTransport;
SemaphoreHandle_t xSemaphore;
bool gotoSystemOffSleep = false;
int work_LED_status = HIGH;

void QSPIF_sleep(void)
{
  flashTransport.begin();
  flashTransport.runCommand(0xB9);
  flashTransport.end();  
}

void setup()
{
  pinMode(LED_RED, OUTPUT);
  pinMode(LED_GREEN, OUTPUT);
  pinMode(LED_BLUE, OUTPUT);
  
  digitalWrite(LED_RED, HIGH);
  digitalWrite(LED_GREEN, HIGH);
  digitalWrite(LED_BLUE, work_LED_status);

  QSPIF_sleep();

  pinMode(DO_WORK_PIN, INPUT_PULLUP_SENSE);
  attachInterrupt(digitalPinToInterrupt(DO_WORK_PIN), doWorkISR, FALLING);

  pinMode(SHUTDOWN_PIN, INPUT_PULLUP_SENSE);
  attachInterrupt(digitalPinToInterrupt(SHUTDOWN_PIN), shutdownISR, FALLING);

  xSemaphore = xSemaphoreCreateBinary();

  // Flash green to see power on, reset, and wake from system_off
  digitalWrite(LED_GREEN, LOW);
  delay(1000);
  digitalWrite(LED_GREEN, HIGH);
}

void doWorkISR()
{
  xSemaphoreGive(xSemaphore);
}

void shutdownISR()
{
  gotoSystemOffSleep = true;
  xSemaphoreGive(xSemaphore);
}

void loop()
{
  // FreeRTOS will automatically put the system in system_on sleep mode here
  xSemaphoreTake(xSemaphore, portMAX_DELAY);

  if (gotoSystemOffSleep)
  {
    //Flash red to see we are going to system_off sleep mode
    digitalWrite(LED_RED, LOW);
    delay(1000);
    digitalWrite(LED_RED, HIGH);

    NRF_POWER->SYSTEMOFF=1; // Execution should not go beyond this
    //sd_power_system_off() // Use this instead if using the soft device
  }

  // Not going to system off sleep mode, so do work
  work_LED_status = !work_LED_status;
  digitalWrite(LED_BLUE, work_LED_status);
}

To get the complete solution I had to rewrite the adafruit/seeed interrupt handler to use low power interrupts (code posted below). If you use gpio interrupts, the best you can do with out of the box adafruit/seeed code is 15ua. (I saw an open issue to implement low power interrupts on the adafruit site.)

The Arduino code is running FreeRTOS underneath the hood, so the techniques published in the Nordic SDK don’t work as expected. I think the __WFE(), __WFI, and maybe sd_app_evt_wait() are intended to run in your main loop with minimal background interrupts/events to cause the loop to wake. FreeRTOS is using RTC1 as a tick timer, so the calls such as __WFI keep unblocking. __WFI will work as expected if you turn off RTC1.

FreeRTOS will automatically put the system in system_on sleep mode and manage RTC1 if all the threads are idle. Underneath the hood it calls __WFE(). You can idle your main thread by calling delay() or by blocking the main thread with a semaphore or other similar primitive. Use a semaphore if you want low latency response time in your main loop.

Here are the results measured with PPK2:

  • System off mode: 1uA
  • gpio interrupts with modified interrupt code
    • Main loop with semaphore: 3uA
    • Main loop with delay(250): 5uA
    • Main loop with delay(100): 8uA
    • Main loop with delay(50): 14uA
  • Gpio interrupts with default interrupt impl: add 12uA to each above
2 Likes

Xiao BLE nrf52840 (and Adafruit feature nrf52840) low power GPIO interrupts.

Someone looking to squeeze out some uAs from their design might find this useful.

The nrf52840 allows both high accuracy higher power as well as low accuracy low power gpio interrupts. The Xiao nrf52840 and Adafruit nrf52840 implementations are using the high accuracy gpio interrupts. (I saw a recent, open issue on the Adafruit site to add low power gpio interrupts.) Using a high accuracy gpio interrupt adds 12-15uAs of power to a design. The low power implementation uses the nrf52 sense mechanism and routes all desired pins to a single event. The interrupt code then needs to loop through and find the actual pin that triggered the interrupt. Hence the “low accuracy” name.

The high accuracy interrupts use the gpiote event channels, so there is a limit of 8 interrupts (it is possible gpio1 somehow adds more, but I didn’t check into that). With the low power interrupts, you can have as many as the software implementation allows. The implementation below allows up to 32 gpio0 interrupts. The code could be extended to also handle gpio1 interrupts.

Nrfx/nrf code is used within the Arduino implementation. That code includes an interrupt handler that allows either high accuracy or low accuracy interrupts on a pin-by-pin basis. However, that code is not enabled (nrfx_gpiote.c). I tried to turn it on, but I couldn’t get it to work, and thought I would run into too many problems using a mix of modules for gpio access.

The code below is based on the low power part of the nrfx code in nrfx_gpiote.c. It stressed my brain to understand the code, so I went for a simpler low power implementation only. However, now that I understand the code, it might not be too hard to implement the more elegant nrfx algorithm that supports both high and low accuracy interrupts. For a real Arduino implementation, it might make sense to use the nrfx code directly for all gpio access. (Maybe that was considered and rejected for some reason.)

This code replaces:
…\packages\Seeeduino\hardware\nrf52\1.1.1\cores\nRF5\WInterrupts.c

Use at your own risk. I debugged and tested just enough to get a two button design to work.

/*
  Copyright (c) 2015 Arduino LLC.  All right reserved.
  Copyright (c) 2016 Sandeep Mistry All right reserved.

  This library is free software; you can redistribute it and/or
  modify it under the terms of the GNU Lesser General Public
  License as published by the Free Software Foundation; either
  version 2.1 of the License, or (at your option) any later version.

  This library is distributed in the hope that it will be useful,
  but WITHOUT ANY WARRANTY; without even the implied warranty of
  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  See the GNU Lesser General Public License for more details.

  You should have received a copy of the GNU Lesser General Public
  License along with this library; if not, write to the Free Software
  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
*/

#include <nrf.h>

#include "Arduino.h"
#include "wiring_private.h"
#include "nrf_gpiote.h"

#include <string.h>

#if defined(NRF52) || defined(NRF52_SERIES)
#define NUMBER_OF_GPIO_TE 8
#else
#define NUMBER_OF_GPIO_TE 4
#endif

#ifdef GPIOTE_CONFIG_PORT_Msk
#define GPIOTE_CONFIG_PORT_PIN_Msk (GPIOTE_CONFIG_PORT_Msk | GPIOTE_CONFIG_PSEL_Msk)
#else
#define GPIOTE_CONFIG_PORT_PIN_Msk GPIOTE_CONFIG_PSEL_Msk
#endif

static voidFuncPtr callbacksInt[NUMBER_OF_GPIO_TE];
static bool callbackDeferred[NUMBER_OF_GPIO_TE];
static int8_t channelMap[NUMBER_OF_GPIO_TE];
static int enabled = 0;

#define GPIOTE_PORT_INTEN_BIT	31
static voidFuncPtr portPinIntCallback[P0_PIN_NUM];
static uint8_t portPinIntPolarity[P0_PIN_NUM];

uint32_t daTestValue[32];

/* Configure I/O interrupt sources */
static void __initialize()
{
  memset(callbacksInt, 0, sizeof(callbacksInt));
  memset(channelMap, -1, sizeof(channelMap));
  memset(callbackDeferred, 0, sizeof(callbackDeferred));
  memset(portPinIntCallback, 0, sizeof(portPinIntCallback));

  NVIC_DisableIRQ(GPIOTE_IRQn);
  NVIC_ClearPendingIRQ(GPIOTE_IRQn);
  NVIC_SetPriority(GPIOTE_IRQn, 3);
  NVIC_EnableIRQ(GPIOTE_IRQn);
}

/*
 * \brief Specifies a named Interrupt Service Routine (ISR) to call when an interrupt occurs.
 *        Replaces any previous function that was attached to the interrupt.
 *
 * \return Interrupt Mask
 */
int attachInterrupt(uint32_t pin, voidFuncPtr callback, uint32_t mode)
{
  if (!enabled) {
    __initialize();
    enabled = 1;
  }

  if (pin >= PINS_COUNT) {
    return 0;
  }

  pin = g_ADigitalPinMap[pin];

  // If first attach, enabled interrupts before return
  bool firstAttach = true;

  for (int ii=0; ii < P0_PIN_NUM; ii++) {
    if (portPinIntCallback[ii]) {
      firstAttach = false;
      break;
    }
  }

  nrf_gpiote_polarity_t polarity;

  switch (mode) {
    case CHANGE:
      polarity = NRF_GPIOTE_POLARITY_TOGGLE;
      break;

    case FALLING:
      polarity = NRF_GPIOTE_POLARITY_HITOLO;
      break;

    case RISING:
      polarity = NRF_GPIOTE_POLARITY_LOTOHI;
      break;

    default:
      return 0;
  }

  portPinIntPolarity[pin] = polarity;
  portPinIntCallback[pin] = callback;

  if (firstAttach) {
    NRF_GPIOTE->EVENTS_PORT = 0;
    NRF_GPIOTE->INTENSET = (1 << GPIOTE_PORT_INTEN_BIT);
  }

  return 8; // 8 is the virtual channel used in nrfx code
}

/*
 * \brief Turns off the given interrupt.
 */
void detachInterrupt(uint32_t pin)
{
  if (pin >= PINS_COUNT) {
    return;
  }

  pin = g_ADigitalPinMap[pin];

  // Clear saved interrupt callback
  portPinIntCallback[pin] = NULL;

  // return if any handlers still registered;
  // otherwise clear the port event interrupt
  for (int ii=0; ii < P0_PIN_NUM; ii++) {
    if (portPinIntCallback[ii]) return;
  }

  NRF_GPIOTE->INTENCLR = (1 << GPIOTE_PORT_INTEN_BIT);
  NRF_GPIOTE->EVENTS_PORT = 0; // clear any final events
}

static bool latch_pending_read_and_check(uint32_t* latch)
{
  // Read and clear the latch
  *latch = NRF_P0->LATCH;
  NRF_P0->LATCH = *latch;

  if (*latch) {
    /* If any of the latch bits is still set, it means another edge has been captured
     * before or during the interrupt processing. Therefore event-processing loop
     * should be executed again. */
    return true;
  }
  return false;
}

void GPIOTE_IRQHandler()
{
#if CFG_SYSVIEW
  SEGGER_SYSVIEW_RecordEnterISR();
#endif

  // If an event is set, then clear the event and handle any valid interrupts
  // associated with the port
  if (NRF_GPIOTE->EVENTS_PORT)
  {
    // clear the event
    NRF_GPIOTE->EVENTS_PORT = 0;

    // Read and clear the latch
    uint32_t latch;
    latch_pending_read_and_check(&latch);

    // Process until latch cleared
    do {

      // Loop over pins
      for (uint32_t pin = 0; pin < P0_PIN_NUM; pin++) {

        // If pin not used then skip to next
        if (portPinIntCallback[pin] == NULL) {
          continue;
        }

        /* Process pin further only if LATCH bit associated with this pin was set. */
        if (latch & (1 << pin)) {
          nrf_gpiote_polarity_t polarity = portPinIntPolarity[pin];	// set in attachInterrupt
          nrf_gpio_pin_sense_t sense =
              (NRF_P0->PIN_CNF[pin] & GPIO_PIN_CNF_SENSE_Msk) >> GPIO_PIN_CNF_SENSE_Pos;

          /* Reconfigure sense to the opposite level, so the internal PINx.DETECT signal
           * can be deasserted. Therefore PORT event generated again,
           * unless some other PINx.DETECT signal is still active.
           * (comment from nrfx code) */
          nrf_gpio_pin_sense_t next_sense =
                    (sense == NRF_GPIO_PIN_SENSE_HIGH) ? NRF_GPIO_PIN_SENSE_LOW :
                                                         NRF_GPIO_PIN_SENSE_HIGH;

          /* set next_sense in sense field in GPIO register*/
          uint32_t cnf = NRF_P0->PIN_CNF[pin] & ~GPIO_PIN_CNF_SENSE_Msk;
          NRF_P0->PIN_CNF[pin] = cnf | (next_sense << GPIO_PIN_CNF_SENSE_Pos);

          /* Try to clear LATCH bit corresponding to currently processed pin.
           * This may not succeed if the pin's state changed during the interrupt processing
           * and now it matches the new sense configuration. In such case,
           * the pin will be processed again in another iteration of the outer loop. */
          NRF_P0->LATCH = (1 << pin);

          /* Invoke user handler only if the sensed pin level
           * matches its polarity configuration. */
          if (((polarity == NRF_GPIOTE_POLARITY_TOGGLE) ||
               (sense == NRF_GPIO_PIN_SENSE_HIGH && polarity == NRF_GPIOTE_POLARITY_LOTOHI) ||
               (sense == NRF_GPIO_PIN_SENSE_LOW && polarity == NRF_GPIOTE_POLARITY_HITOLO))) {
            portPinIntCallback[pin]();
          }
        } // if latch bit set
      } // for each pin
    } while (latch_pending_read_and_check(&latch));
  } // port event

#if __CORTEX_M == 0x04
  // See note at nRF52840_PS_v1.1.pdf section 6.1.8 ("interrupt clearing")
  // See also https://gcc.gnu.org/onlinedocs/gcc/Volatiles.html for why
  // using memory barrier instead of read of an unrelated volatile
  __DSB(); __NOP();__NOP();__NOP();__NOP();
#endif

#if CFG_SYSVIEW
  SEGGER_SYSVIEW_RecordExitISR();
#endif
}

@DBurd49ers
I modified the sketch I posted. I added Bluefruit.begin() and switched
NRF_POWER->SYSTEMOFF=1; to sd_power_system_off(); I also went back to the default arduino implementation for gpio interrupts.
I measure 15uA when the loop is running (system on sleep mode) and 1uA for system off. If your test code doesn’t use the gpio interrupts, then you should see 3uA while the loop is running.

You don’t need the call sd_power_mode_set(NRF_POWER_MODE_LOWPWR) that is for the system on sleep mode and is the default in any case.

I tried DCDC_ENABLE in combination with many other things previously. I may need to test that again now that I have a good baseline. It was the default in Zephyr RTOS, that may be the case here as well.

@daCoder . I am working with @DBurd49ers on trying to optimize the sleep mode.

Here is the current code we are using:

#include "LSM6DS3.h"
#include "Wire.h"
#include <Arduino.h>
/*#include <SPI.h>
#include <SdFat.h>*/
#include <Adafruit_FlashTransport.h>
// for flashTransport definition
//#include "flash_config.h"
#include <bluefruit.h>
//#include <ArduinoBLE.h>
//#include <LowPower.h>

//const int slaveSelectPin = 12;

//Adafruit_FlashTransport_QSPI flashTransport;
 
//BLEService ledService("3ac82d02-002b-4ccb-b68c-1c7839cbc4c0");

byte accelArray[16];

//BLEByteCharacteristic switchCharacteristic("19B10001-E8F2-537E-4F6C-D104768A1214", BLERead | BLEWrite);
//BLECharacteristic switchCharacteristic("3ac82d02-002b-4ccb-b68c-1c7839cbc4c0", BLERead | BLEWrite, sizeof(accelArray), true);

LSM6DS3 myIMU(I2C_MODE, 0x6A);
#define intPin PIN_LSM6DS3TR_C_INT1

int interrupts_received = 0;
int prev_interrupts_received = 0;
int no_change = 0;
int ble_enabled = 0;
int work_LED_status = HIGH;

#define MANUFACTURER_ID   0x0059

// "nRF Connect" app can be used to detect beacon
uint8_t beaconUuid[16] =
{
  0x01, 0x12, 0x23, 0x34, 0x45, 0x56, 0x67, 0x78,
  0x89, 0x9a, 0xab, 0xbc, 0xcd, 0xde, 0xef, 0xf0
};

// A valid Beacon packet consists of the following information:
// UUID, Major, Minor, RSSI @ 1M
BLEBeacon beacon(beaconUuid, 0x0102, 0x0304, -54);

void setup() {

  pinMode(LED_RED, OUTPUT);
  pinMode(LED_GREEN, OUTPUT);
  pinMode(LED_BLUE, OUTPUT);
  
  digitalWrite(LED_RED, HIGH);
  digitalWrite(LED_GREEN, HIGH);
  digitalWrite(LED_BLUE, work_LED_status);

    Adafruit_FlashTransport_QSPI flashTransport;

    Bluefruit.begin();
    Bluefruit.setName("Ver Mac Device 1"); 
    Bluefruit.setTxPower(-40); 
    // off Blue LED for lowest power consumption
    Bluefruit.autoConnLed(false);
    //Bluefruit.setTxPower(4);    // Check bluefruit.h for supported values

    // Manufacturer ID is required for Manufacturer Specific Data
    beacon.setManufacturer(MANUFACTURER_ID);

    // Setup the advertising packet
    startAdv();

  

    flashTransport.begin();
    flashTransport.runCommand(0xB9);
    flashTransport.end();

    //myIMU.settings.gyroEnabled = 0; // Gyro currently not used, disabled to save power
    if (myIMU.begin() != 0) {
        //Serial.println("Device error");
    } else {
        //Serial.println("Device OK!");
    }

    delay(300);

    setupSingleTapInterrupt();
    

    pinMode(intPin, INPUT);
    attachInterrupt(digitalPinToInterrupt(intPin), intIncrementer, LOW);
}

void startAdv(void)
{  
  // Advertising packet
  // Set the beacon payload using the BLEBeacon class populated
  // earlier in this example
  Bluefruit.Advertising.setBeacon(beacon);

  // Secondary Scan Response packet (optional)
  // Since there is no room for 'Name' in Advertising packet
  Bluefruit.ScanResponse.addName();
  
  /* Start Advertising
   * - Enable auto advertising if disconnected
   * - Timeout for fast mode is 30 seconds
   * - Start(timeout) with timeout = 0 will advertise forever (until connected)
   * 
   * Apple Beacon specs
   * - Type: Non connectable, undirected
   * - Fixed interval: 100 ms -> fast = slow = 100 ms
   */
  //Bluefruit.Advertising.setType(BLE_GAP_ADV_TYPE_ADV_NONCONN_IND);
  Bluefruit.Advertising.restartOnDisconnect(true);
  Bluefruit.Advertising.setInterval(3067, 3067);    // in unit of 0.625 ms
  Bluefruit.Advertising.setFastTimeout(30);      // number of seconds in fast mode
  Bluefruit.Advertising.start(0);                // 0 = Don't stop advertising after n seconds  
}

void loop() {

    delay(100);

    if (no_change >= 60)
    {
        //setLedRGB(true, false, false);
        //delay(10000);
        setLedRGB(false, false, false);
        //delay(10000);
        lowPowerMode();
    }

    if (interrupts_received > prev_interrupts_received)
    {
        prev_interrupts_received = interrupts_received;
        no_change = 0;
    }
    else
    {
        //setLedRGB(true, false, false);
        //delay(100);
        no_change++;
    }
}

void setupSingleTapInterrupt()
{
    myIMU.writeRegister(LSM6DS3_ACC_GYRO_CTRL1_XL, 0x60);
    myIMU.writeRegister(LSM6DS3_ACC_GYRO_TAP_CFG1, 0x8E);
    myIMU.writeRegister(LSM6DS3_ACC_GYRO_TAP_THS_6D, 0x80);
    myIMU.writeRegister(LSM6DS3_ACC_GYRO_INT_DUR2, 0x7F);
    myIMU.writeRegister(LSM6DS3_ACC_GYRO_WAKE_UP_THS, 0x01);
    myIMU.writeRegister(LSM6DS3_ACC_GYRO_MD1_CFG, 0x20);
}

void lowPowerMode()
{
    //Serial.println(F("Powering down system!"));
    nrf_gpio_cfg_sense_input(digitalPinToInterrupt(intPin), NRF_GPIO_PIN_PULLDOWN, NRF_GPIO_PIN_SENSE_HIGH);
    delay(1000);
    sd_power_system_off();
    NRF_POWER->SYSTEMOFF = 1;
    /*sd_power_mode_set(NRF_POWER_MODE_LOWPWR);

    sd_power_dcdc_mode_set(NRF_POWER_DCDC_ENABLE);

    sd_power_system_off();*/
}

void intIncrementer() 
{
    interrupts_received++;
}

void setLedRGB(bool red, bool green, bool blue) {
  //if (!blue) { digitalWrite(LEDB, HIGH); } else { digitalWrite(LEDB, LOW); }
  //if (!green) { digitalWrite(LEDG, HIGH); } else { digitalWrite(LEDG, LOW); }
  if (!red) { digitalWrite(LED_BUILTIN, HIGH); } else { digitalWrite(LED_BUILTIN, LOW); }
}

I believe our IMU interrupt is not working but trying to understand if this is related to the proper PIN setup or the soft device ignoring the interrupt when sleeping? Any advise on how to work around this?

1 Like

@jptalledo I’m not sure of your root question. Is it getting the LSM6DS3 interrupt working or deep sleep? In either case, I would recommend stripping the code down to the minimum required for each aspect (e.g. deep sleep vs interrupt), then get that specific aspect working. After that add back other parts such as Bluetooth.

I only have the plain xiao nrf52840 so don’t have experience with the LSM6DS3. I did see reports of deep sleep and double tap interrupts on the topic page I linked above.

Optimizing Power On nrf52 Designs

This Nordic page might be useful to solve power issues. This is what clued me in on the interrupt issue.

Hi jptalledo,
Have you tried it this way?

attachInterrupt(digitalPinToInterrupt(int2Pin), int1ISR, RISING);

HTH
GL :slight_smile: PJ

Nordic Online Power Profiler for Bluetooth LE

The above link to the Nordic Online Profiler was a useful resource. Once I had the baseline current usage worked out without Bluetooth, I then used this to verify whether current usage during advertising and connection was as expected.

I confirmed with a test that NRF_POWER_MODE_LOWPWR is the default once in the setup loop, so no need to explicitly enabled this. When I turned on constant latency mode the idle loop power increased to 377uA.

I also found that the DC/DC converter is NOT enabled by default. This does not impact the idle mode power, however, this does impact the advertising and connection power. I didn’t test this directly, but the online power profiler linked above shows significant savings with the DC/DC converter enabled.

Looks like the proper call to enable the DC/DC converter with the soft device is: sd_power_dcdc_mode_set(NRF_POWER_DCDC_ENABLE);

nRF5x Power Management Tutorial

This tutorial had some useful info on power management. This is for the nrf SDK, so not everything is relevant.

Did you manage to get wakeup by accelerometer interrupt working?

Do you a code sample with wakeup by accelerometer interrupt?

Can you add the handing of accelerometer interrupt for Xiao Ble Sense?

I don’t have the sense version of the xiao.

This page has code snippets for the accelerometer interrupt: XIAO BLE Sense in deep sleep mode

Hi @Ivan_Arakistain_Mark

I picked up a sense and played around with the accelerometer. If you’re still looking for accelerometer info I posted some info here: Xiao Sense Accelerometer Examples and Low Power. Seemed complicated enough to be its own topic.

I’m trying to make a datalogger for a bucket rain gauge.The rain is filling the bucket. When the bucket is full, it is turning and triggering a contact with a magnet. One have to record the contact with timestamp. I’m using BLE for initial configuration (including time) and to retrieve data. So, most of the time, BLE is off and I will start it by pushing a button.

Now, I’m trying to use the XIAO nRF52840 without Sense. Non-mbed version 1.1.1. Current is measured on a 18650 LiPo connected to Bat’s pins.

  • Blink using delay in the main loop (when LED off): 21 µA
  • Blink with timer/callback and suspendLoop() : 21 µA
  • same as previous + attachInterrupt(raingaugePin, raingauge_callback, ISR_DEFERRED | FALLING) : 38 µA

Why such an increase? Can I minimize it?

@daCoder , I have questions on what you proposed. In your code with semaphore, you are using System Off Sleep. I think I can’t use it because I need to preserve timing function. I’m using xTaskGetTickCount(). Is my high power consumption increase related to high accuracy gpio management? Should your low accuracy version of the interrupts library improve this?

what are yall using to monitor power usage? do you have a particular device or data logger?

25 € multimeter: