Low power mode on NRF52832 with LSM6DSO trigger based wakeup and Bluetooth

Hello,

I'm working on a project that involves using an NRF52832. Basically, I want to collect data, send it over bluetooth, and then have the device enter system_off mode. If the IMU feels a certain acceleration threshold, the device will power on, and once again collect/send data before powering off. I've talked more about some issues I was having here, but things currently work (for the most part). The issue that I am now having is that although my device seems to go in system_off mode, it still seems to draw about 10.5mA (normal operation before power down occurs at 13.5mA). Obviously something is working since the current reduces, but it's still very high. I do use 1 IMU to trigger wakeup, but it shouldn't be drawing this much power on its own. I need help figuring out what might still be enabled that is causing the current draw to stay high even when my device should be in system_off mode. I'll share my code below as well as my devicetree and config files. Thank you for the help!

//connor shannon wrote this, be careful changing stuff or it might break
//necessary include statements here
//--------------------------------------------------------------------------------------------------------------------
#include <uart_async_adapter.h>
#include <zephyr/types.h>
#include <zephyr/kernel.h>
#include <zephyr/drivers/uart.h>
#include <zephyr/usb/usb_device.h>
#include <zephyr/device.h>
#include <zephyr/devicetree.h>
#include <soc.h>
#include <zephyr/bluetooth/bluetooth.h>
#include <zephyr/bluetooth/uuid.h>
#include <zephyr/bluetooth/gatt.h>
#include <zephyr/bluetooth/hci.h>
#include <bluetooth/services/nus.h>
#include <dk_buttons_and_leds.h>
#include <zephyr/settings/settings.h>
#include <stdio.h>
#include <string.h>
#include <stdint.h>
#include <zephyr/logging/log.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/sys/ring_buffer.h>
#include <zephyr/drivers/adc.h>
#include <zephyr/drivers/gpio.h>

#include <zephyr/drivers/i2c.h>
#include <hal/nrf_gpio.h>
#include <nrfx_power.h>
#include <hal/nrf_power.h>

//and define statments
#define STACKSIZE CONFIG_BT_NUS_THREAD_STACK_SIZE
#define PRIORITY 7
#define DEVICE_NAME CONFIG_BT_DEVICE_NAME
#define DEVICE_NAME_LEN	(sizeof(DEVICE_NAME) - 1)
#define RUN_STATUS_LED DK_LED1
#define RUN_LED_BLINK_INTERVAL 1000
#define CON_STATUS_LED DK_LED2
#define KEY_PASSKEY_ACCEPT DK_BTN1_MSK
#define KEY_PASSKEY_REJECT DK_BTN2_MSK
#define UART_BUF_SIZE CONFIG_BT_NUS_UART_BUFFER_SIZE
#define UART_WAIT_FOR_BUF_DELAY K_MSEC(50)
#define UART_WAIT_FOR_RX CONFIG_BT_NUS_UART_RX_WAIT_TIME
#define RAD_TO_DEGREE 57.2958
#define GRAVITY 9.80665
#define DECIMAL_SHIFT 1000
#define SAMPLING_FREQUENCY 104 //set sampling freq
#define ACTIVE_MODE 1 //set mode. Active mode should be 1 if using device normallyy
#define BUFFER_SIZE 8000  // size of ring buffer, as in number of elements
#define RING_BUF_SIZE (BUFFER_SIZE * sizeof(int32_t))  // Total size in bytes
RING_BUF_DECLARE(my_ring_buffer, RING_BUF_SIZE); //declaration of ring bfufer
#define ADC_BUFFER_SIZE 100  // size of adc buffer, as in number of elements
#define ADC_RING_BUF_SIZE (ADC_BUFFER_SIZE * sizeof(int32_t))  // Total size in bytes
RING_BUF_DECLARE(adc_ring_buffer, ADC_RING_BUF_SIZE);  //declaration of adc ring buffer
uint16_t time_ms = 0; //define a global variable to track time
#define TESTING_MODE 0 //more testing stuff
#define ADC_MODE 1
#define GPIO_NODE DT_NODELABEL(gpio0)

//lines below added for low power implementation and trigger mode
#define INT1_NODE DT_ALIAS(lsm6dso_int1)

#if DT_NODE_HAS_STATUS(INT1_NODE, okay)
static const struct gpio_dt_spec int1_gpio = GPIO_DT_SPEC_GET(INT1_NODE, irq_gpios);
#else
#error "INT1_NODE is not defined or not okay in the device tree"
#endif
static struct gpio_callback int1_cb_data;


// Replace with correct label from your board's devicetree if needed
#define I2C_BUS DT_NODELABEL(i2c0)
#define LSM6DSO_I2C_ADDR 0x6B 

static const struct device *i2c_dev = DEVICE_DT_GET(I2C_BUS);

static int lsm6dso_write_reg(uint8_t reg, uint8_t val) {
	return i2c_reg_write_byte(i2c_dev, LSM6DSO_I2C_ADDR, reg, val);
}

static int lsm6dso_read_reg(uint8_t reg, uint8_t *val) {
	return i2c_reg_read_byte(i2c_dev, LSM6DSO_I2C_ADDR, reg, val);
}

void scl_toggle(void) {
    const struct device *scl_port = DEVICE_DT_GET(DT_NODELABEL(gpio0));
    const uint8_t scl_pin = 20;

    gpio_pin_configure(scl_port, scl_pin, GPIO_OUTPUT);

    for (int i = 0; i < 9; i++) {
        gpio_pin_set(scl_port, scl_pin, 1);
        k_busy_wait(5);
        gpio_pin_set(scl_port, scl_pin, 0);
        k_busy_wait(5);
    }

    gpio_pin_configure(scl_port, scl_pin, GPIO_INPUT); // optional reset
}


//--------------------------------------------------------------------------------------------------------------

//all necessary random and initialization-type functions here (these functions should not need edits)

static inline float out_ev(struct sensor_value *val)
{
	return (val->val1 + (float)val->val2 / 1000000);
}

static int set_sampling_freq(const struct device *dev)
{
	int ret = 0;
	struct sensor_value odr_attr;

	/* set accel/gyro sampling frequency to 12.5 Hz */
	odr_attr.val1 = SAMPLING_FREQUENCY;
	//odr_attr.val1 = 12.5;
	odr_attr.val2 = 0;

	ret = sensor_attr_set(dev, SENSOR_CHAN_ACCEL_XYZ,
			SENSOR_ATTR_SAMPLING_FREQUENCY, &odr_attr);
	if (ret != 0) {
		printf("Cannot set sampling frequency for accelerometer.\n");
		return ret;
	}

	ret = sensor_attr_set(dev, SENSOR_CHAN_GYRO_XYZ,
			SENSOR_ATTR_SAMPLING_FREQUENCY, &odr_attr);
	if (ret != 0) {
		printf("Cannot set sampling frequency for gyro.\n");
		return ret;
	}

	return 0;
}

static K_SEM_DEFINE(ble_init_ok, 0, 1);

static struct bt_conn *current_conn;
static struct bt_conn *auth_conn;

static const struct device *uart = DEVICE_DT_GET(DT_CHOSEN(nordic_nus_uart));
static struct k_work_delayable uart_work;

struct uart_data_t {
	void *fifo_reserved;
	uint8_t data[UART_BUF_SIZE];
	uint16_t len;
};

static K_FIFO_DEFINE(fifo_uart_tx_data);
static K_FIFO_DEFINE(fifo_uart_rx_data);

static const struct bt_data ad[] = {
	BT_DATA_BYTES(BT_DATA_FLAGS, (BT_LE_AD_GENERAL | BT_LE_AD_NO_BREDR)),
	BT_DATA(BT_DATA_NAME_COMPLETE, DEVICE_NAME, DEVICE_NAME_LEN),
};

static const struct bt_data sd[] = {
	BT_DATA_BYTES(BT_DATA_UUID128_ALL, BT_UUID_NUS_VAL),
};

#ifdef CONFIG_UART_ASYNC_ADAPTER
UART_ASYNC_ADAPTER_INST_DEFINE(async_adapter);
#else
#define async_adapter NULL
#endif

static void uart_cb(const struct device *dev, struct uart_event *evt, void *user_data)
{
	ARG_UNUSED(dev);

	static size_t aborted_len;
	struct uart_data_t *buf;
	static uint8_t *aborted_buf;
	static bool disable_req;

	switch (evt->type) {
	case UART_TX_DONE:
		//LOG_DBG("UART_TX_DONE");
		if ((evt->data.tx.len == 0) ||
		    (!evt->data.tx.buf)) {
			return;
		}

		if (aborted_buf) {
			buf = CONTAINER_OF(aborted_buf, struct uart_data_t,
					   data[0]);
			aborted_buf = NULL;
			aborted_len = 0;
		} else {
			buf = CONTAINER_OF(evt->data.tx.buf, struct uart_data_t,
					   data[0]);
		}

		k_free(buf);

		buf = k_fifo_get(&fifo_uart_tx_data, K_NO_WAIT);
		if (!buf) {
			return;
		}

		if (uart_tx(uart, buf->data, buf->len, SYS_FOREVER_MS)) {
			//LOG_WRN("Failed to send data over UART");
		}

		break;

	case UART_RX_RDY:
		//LOG_DBG("UART_RX_RDY");
		buf = CONTAINER_OF(evt->data.rx.buf, struct uart_data_t, data[0]);
		buf->len += evt->data.rx.len;

		if (disable_req) {
			return;
		}

		if ((evt->data.rx.buf[buf->len - 1] == '\n') ||
		    (evt->data.rx.buf[buf->len - 1] == '\r')) {
			disable_req = true;
			uart_rx_disable(uart);
		}

		break;

	case UART_RX_DISABLED:
		//LOG_DBG("UART_RX_DISABLED");
		disable_req = false;

		buf = k_malloc(sizeof(*buf));
		if (buf) {
			buf->len = 0;
		} else {
			//LOG_WRN("Not able to allocate UART receive buffer");
			k_work_reschedule(&uart_work, UART_WAIT_FOR_BUF_DELAY);
			return;
		}

		uart_rx_enable(uart, buf->data, sizeof(buf->data),
			       UART_WAIT_FOR_RX);

		break;

	case UART_RX_BUF_REQUEST:
		//LOG_DBG("UART_RX_BUF_REQUEST");
		buf = k_malloc(sizeof(*buf));
		if (buf) {
			buf->len = 0;
			uart_rx_buf_rsp(uart, buf->data, sizeof(buf->data));
		} else {
			//LOG_WRN("Not able to allocate UART receive buffer");
		}

		break;

	case UART_RX_BUF_RELEASED:
		//LOG_DBG("UART_RX_BUF_RELEASED");
		buf = CONTAINER_OF(evt->data.rx_buf.buf, struct uart_data_t,
				   data[0]);

		if (buf->len > 0) {
			k_fifo_put(&fifo_uart_rx_data, buf);
		} else {
			k_free(buf);
		}

		break;

	case UART_TX_ABORTED:
		//LOG_DBG("UART_TX_ABORTED");
		if (!aborted_buf) {
			aborted_buf = (uint8_t *)evt->data.tx.buf;
		}

		aborted_len += evt->data.tx.len;
		buf = CONTAINER_OF((void *)aborted_buf, struct uart_data_t,
				   data);

		uart_tx(uart, &buf->data[aborted_len],
			buf->len - aborted_len, SYS_FOREVER_MS);

		break;

	default:
		break;
	}
}

static void uart_work_handler(struct k_work *item)
{
	struct uart_data_t *buf;

	buf = k_malloc(sizeof(*buf));
	if (buf) {
		buf->len = 0;
	} else {
		//LOG_WRN("Not able to allocate UART receive buffer");
		k_work_reschedule(&uart_work, UART_WAIT_FOR_BUF_DELAY);
		return;
	}

	uart_rx_enable(uart, buf->data, sizeof(buf->data), UART_WAIT_FOR_RX);
}

static bool uart_test_async_api(const struct device *dev)
{
	const struct uart_driver_api *api =
			(const struct uart_driver_api *)dev->api;

	return (api->callback_set != NULL);
}

static int uart_init(void)
{
	int err;
	int pos;
	struct uart_data_t *rx;
	struct uart_data_t *tx;

	if (!device_is_ready(uart)) {
		return -ENODEV;
	}

	if (IS_ENABLED(CONFIG_USB_DEVICE_STACK)) {
		err = usb_enable(NULL);
		if (err && (err != -EALREADY)) {
			printf("Failed to enable USB");
			return err;
		}
	}

	rx = k_malloc(sizeof(*rx));
	if (rx) {
		rx->len = 0;
	} else {
		return -ENOMEM;
	}

	k_work_init_delayable(&uart_work, uart_work_handler);


	if (IS_ENABLED(CONFIG_UART_ASYNC_ADAPTER) && !uart_test_async_api(uart)) {
		/* Implement API adapter */
		uart_async_adapter_init(async_adapter, uart);
		uart = async_adapter;
	}

	err = uart_callback_set(uart, uart_cb, NULL);
	if (err) {
		k_free(rx);
		printf("Cannot initialize UART callback");
		return err;
	}

	if (IS_ENABLED(CONFIG_UART_LINE_CTRL)) {
		//LOG_INF("Wait for DTR");
		while (true) {
			uint32_t dtr = 0;

			uart_line_ctrl_get(uart, UART_LINE_CTRL_DTR, &dtr);
			if (dtr) {
				break;
			}
			/* Give CPU resources to low priority threads. */
			k_sleep(K_MSEC(100));
		}
		//LOG_INF("DTR set");
		err = uart_line_ctrl_set(uart, UART_LINE_CTRL_DCD, 1);
		if (err) {
			//LOG_WRN("Failed to set DCD, ret code %d", err);
		}
		err = uart_line_ctrl_set(uart, UART_LINE_CTRL_DSR, 1);
		if (err) {
			//LOG_WRN("Failed to set DSR, ret code %d", err);
		}
	}

	tx = k_malloc(sizeof(*tx));

	if (tx) {
		pos = snprintf(tx->data, sizeof(tx->data),
			       "Code written by Connor Shannon\r\n");

		if ((pos < 0) || (pos >= sizeof(tx->data))) {
			k_free(rx);
			k_free(tx);
			printf("snprintf returned %d", pos);
			return -ENOMEM;
		}

		tx->len = pos;
	} else {
		k_free(rx);
		return -ENOMEM;
	}

	err = uart_tx(uart, tx->data, tx->len, SYS_FOREVER_MS);
	if (err) {
		k_free(rx);
		k_free(tx);
		printf("Cannot display welcome message (err: %d)", err);
		return err;
	}

	err = uart_rx_enable(uart, rx->data, sizeof(rx->data), UART_WAIT_FOR_RX);
	if (err) {
		printf("Cannot enable uart reception (err: %d)", err);
		/* Free the rx buffer only because the tx buffer will be handled in the callback */
		k_free(rx);
	}

	return err;
}

static void connected(struct bt_conn *conn, uint8_t err)
{
	char addr[BT_ADDR_LE_STR_LEN];

	if (err) {
		printf("Connection failed (err %u)", err);
		return;
	}

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));
	//LOG_INF("Connected %s", addr);

	current_conn = bt_conn_ref(conn);

	dk_set_led_on(CON_STATUS_LED);
}

static void disconnected(struct bt_conn *conn, uint8_t reason)
{
	char addr[BT_ADDR_LE_STR_LEN];

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));

	//LOG_INF("Disconnected: %s (reason %u)", addr, reason);

	if (auth_conn) {
		bt_conn_unref(auth_conn);
		auth_conn = NULL;
	}

	if (current_conn) {
		bt_conn_unref(current_conn);
		current_conn = NULL;
		dk_set_led_off(CON_STATUS_LED);
	}
}

#ifdef CONFIG_BT_NUS_SECURITY_ENABLED
static void security_changed(struct bt_conn *conn, bt_security_t level,
			     enum bt_security_err err)
{
	char addr[BT_ADDR_LE_STR_LEN];

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));

	if (!err) {
		//LOG_INF("Security changed: %s level %u", addr, level);
	} else {
		//LOG_WRN("Security failed: %s level %u err %d", addr,
		//	level, err);
	}
}
#endif

BT_CONN_CB_DEFINE(conn_callbacks) = {
	.connected    = connected,
	.disconnected = disconnected,
#ifdef CONFIG_BT_NUS_SECURITY_ENABLED
	.security_changed = security_changed,
#endif
};

#if defined(CONFIG_BT_NUS_SECURITY_ENABLED)
static void auth_passkey_display(struct bt_conn *conn, unsigned int passkey)
{
	char addr[BT_ADDR_LE_STR_LEN];

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));

	//LOG_INF("Passkey for %s: %06u", addr, passkey);
}

static void auth_passkey_confirm(struct bt_conn *conn, unsigned int passkey)
{
	char addr[BT_ADDR_LE_STR_LEN];

	auth_conn = bt_conn_ref(conn);

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));

	//LOG_INF("Passkey for %s: %06u", addr, passkey);
	//LOG_INF("Press Button 1 to confirm, Button 2 to reject.");
}


static void auth_cancel(struct bt_conn *conn)
{
	char addr[BT_ADDR_LE_STR_LEN];

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));

	//LOG_INF("Pairing cancelled: %s", addr);
}


static void pairing_complete(struct bt_conn *conn, bool bonded)
{
	char addr[BT_ADDR_LE_STR_LEN];

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));

	//LOG_INF("Pairing completed: %s, bonded: %d", addr, bonded);
}


static void pairing_failed(struct bt_conn *conn, enum bt_security_err reason)
{
	char addr[BT_ADDR_LE_STR_LEN];

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, sizeof(addr));

	//LOG_INF("Pairing failed conn: %s, reason %d", addr, reason);
}


static struct bt_conn_auth_cb conn_auth_callbacks = {
	.passkey_display = auth_passkey_display,
	.passkey_confirm = auth_passkey_confirm,
	.cancel = auth_cancel,
};

static struct bt_conn_auth_info_cb conn_auth_info_callbacks = {
	.pairing_complete = pairing_complete,
	.pairing_failed = pairing_failed
};
#else
static struct bt_conn_auth_cb conn_auth_callbacks;
static struct bt_conn_auth_info_cb conn_auth_info_callbacks;
#endif

static void bt_receive_cb(struct bt_conn *conn, const uint8_t *const data,
			  uint16_t len)
{
	int err;
	char addr[BT_ADDR_LE_STR_LEN] = {0};

	bt_addr_le_to_str(bt_conn_get_dst(conn), addr, ARRAY_SIZE(addr));

	//LOG_INF("Received data from: %s", addr);

	for (uint16_t pos = 0; pos != len;) {
		struct uart_data_t *tx = k_malloc(sizeof(*tx));

		if (!tx) {
			//LOG_WRN("Not able to allocate UART send data buffer");
			return;
		}

		/* Keep the last byte of TX buffer for potential LF char. */
		size_t tx_data_size = sizeof(tx->data) - 1;

		if ((len - pos) > tx_data_size) {
			tx->len = tx_data_size;
		} else {
			tx->len = (len - pos);
		}

		memcpy(tx->data, &data[pos], tx->len);

		pos += tx->len;

		/* Append the LF character when the CR character triggered
		 * transmission from the peer.
		 */
		if ((pos == len) && (data[len - 1] == '\r')) {
			tx->data[tx->len] = '\n';
			tx->len++;
		}

		err = uart_tx(uart, tx->data, tx->len, SYS_FOREVER_MS);
		if (err) {
			k_fifo_put(&fifo_uart_tx_data, tx);
		}
	}
}

static struct bt_nus_cb nus_cb = {
	.received = bt_receive_cb,
};

void error(void)
{
	dk_set_leds_state(DK_ALL_LEDS_MSK, DK_NO_LEDS_MSK);

	while (true) {
		/* Spin for ever */
		k_sleep(K_MSEC(1000));
	}
}

#ifdef CONFIG_BT_NUS_SECURITY_ENABLED
static void num_comp_reply(bool accept)
{
	if (accept) {
		bt_conn_auth_passkey_confirm(auth_conn);
		//LOG_INF("Numeric Match, conn %p", (void *)auth_conn);
	} else {
		bt_conn_auth_cancel(auth_conn);
		//LOG_INF("Numeric Reject, conn %p", (void *)auth_conn);
	}

	bt_conn_unref(auth_conn);
	auth_conn = NULL;
}

void button_changed(uint32_t button_state, uint32_t has_changed)
{
	uint32_t buttons = button_state & has_changed;

	if (auth_conn) {
		if (buttons & KEY_PASSKEY_ACCEPT) {
			num_comp_reply(true);
		}

		if (buttons & KEY_PASSKEY_REJECT) {
			num_comp_reply(false);
		}
	}
}
#endif /* CONFIG_BT_NUS_SECURITY_ENABLED */

static void configure_gpio(void)
{
	int err;

#ifdef CONFIG_BT_NUS_SECURITY_ENABLED
	err = dk_buttons_init(button_changed);
	if (err) {
		printf("Cannot init buttons (err: %d)", err);
	}
#endif /* CONFIG_BT_NUS_SECURITY_ENABLED */

	err = dk_leds_init();
	if (err) {
		printf("Cannot init LEDs (err: %d)", err);
	}
}


//____________________________________________________________________________________________________________________________________________________________

//all functions above this should not need editing, while all functions below this are more important and may require editing

//____________________________________________________________________________________________________________________________________________________________

/**
 * Combines two 16-bit integers into a single 32-bit integer.
 * @param value1 The first 16-bit integer (to be placed in the upper 16 bits).
 * @param value2 The second 16-bit integer (to be placed in the lower 16 bits).
 * @return A 32-bit integer containing both input values.
 */
uint32_t pack_16bit_to_32bit(int16_t value1, int16_t value2) {
    return ((uint32_t)(uint16_t)value1 << 16) | (uint16_t)value2;
}

/**
 * Extracts the first (upper) 16-bit integer from a 32-bit integer.
 * @param packed_value The 32-bit integer containing two 16-bit integers.
 * @return The first (upper) 16-bit integer.
 */
int16_t extract_first_16bit(uint32_t packed_value) {
    return (int16_t)(packed_value >> 16);  // Ensure sign extension
}

/**
 * Extracts the second (lower) 16-bit integer from a 32-bit integer.
 * @param packed_value The 32-bit integer containing two 16-bit integers.
 * @return The second (lower) 16-bit integer.
 */
int16_t extract_second_16bit(uint32_t packed_value) {
    return (int16_t)(packed_value & 0xFFFF);  // Implicitly sign-extended
}

// Add a 32-bit integer to the ring buffer
int add_to_ring_buffer(struct ring_buf *rb, uint32_t data) {
    int ret = ring_buf_put(rb, (uint8_t *)&data, sizeof(data));
    return (ret == sizeof(data)) ? 1 : 0; // Return 1 if all bytes were written, 0 otherwise
}

// Check if the ring buffer is full
int is_ring_buffer_full(struct ring_buf *rb) {
    return ring_buf_space_get(rb) == 0 ? 1 : 0; // Return 1 if full, 0 if not
}


// Get a 32-bit integer from the ring buffer
int get_from_ring_buffer(struct ring_buf *rb, uint32_t *data) {
    // Attempt to retrieve the first 32-bit value (4 bytes) from the ring buffer
    int ret = ring_buf_get(rb, (uint8_t *)data, sizeof(uint32_t));

    if (ret == sizeof(uint32_t)) {
        return 1; // Successfully retrieved the first value
    } else {
        return 0; // Failed to retrieve (buffer might be empty)
    }
}

// Check if the ring buffer is empty
int is_ring_buffer_empty(struct ring_buf *rb) {
    return ring_buf_is_empty(rb) ? 1 : 0; // Return 1 if empty, 0 if not
}


//check if bluetooth is connected
bool is_bt_connected(void)
{
    return (current_conn != NULL);
}

static int64_t time_reset_reference = 0;

void reset_time_reference(void) { //resets time value every time data collection begins
    time_reset_reference = k_uptime_get();
}

int16_t get_elapsed_time_ms(void) { //uses the reference time to get elapsed time since start of data collection
    int64_t current_time = k_uptime_get();
    int64_t elapsed_time = current_time - time_reset_reference;

    // Safely cast to uint16_t
    return (int16_t)(elapsed_time & 0xFFFF); // Wrap around at 16 bits
}
void check_ring_buffer_progress(size_t total_elements) {
    static uint32_t call_count = 0;  // Tracks how many times the function is called
	//uint16_t time;
    // Increment the call count
    call_count++;

    // Only print every 100 calls
    if (call_count % 100 == 0) {
        // Get the current used space in bytes
        size_t used_space = ring_buf_size_get(&my_ring_buffer);  

        // Convert used space (in bytes) to number of elements
        size_t used_elements = used_space / sizeof(uint32_t);  // Assuming uint32_t (4 bytes each)

        // Calculate the percentage of the buffer that is full
        uint8_t current_percent = (used_elements * 100) / total_elements;

        // Print the buffer percentage
        printf("Ring buffer is %d%% full\n", current_percent);

		//time = get_elapsed_time_ms();
		//printf("Elapsed time: %d\n", time);
    }
}


void get_LSM6DSO_data(const struct device *dev){ //this function gets and stores 6 values from the sensor
	struct sensor_value x, y, z;
	int16_t pack1;
	int16_t pack2;
	uint32_t data_to_store;
	int full;

	sensor_sample_fetch_chan(dev, SENSOR_CHAN_GYRO_XYZ);
	sensor_channel_get(dev, SENSOR_CHAN_GYRO_X, &x);
	sensor_channel_get(dev, SENSOR_CHAN_GYRO_Y, &y);
	sensor_channel_get(dev, SENSOR_CHAN_GYRO_Z, &z);
	
	if (TESTING_MODE == 1){
		printf("Raw gyro X: %d, %d\n", x.val1, x.val2);
    	printf("Raw gyro Y: %d, %d\n", y.val1, y.val2);
    	printf("Raw gyro Z: %d, %d\n", z.val1, z.val2);
		k_sleep(K_MSEC(500));
	}

	//package x and y gyro, store
	pack1 = (int16_t)(out_ev(&x)*(float)DECIMAL_SHIFT*(float)RAD_TO_DEGREE);
	pack2 = (int16_t)(out_ev(&y)*(float)DECIMAL_SHIFT*(float)RAD_TO_DEGREE);
	data_to_store = pack_16bit_to_32bit(pack1, pack2);
	full = add_to_ring_buffer(&my_ring_buffer, data_to_store); 

	if (TESTING_MODE == 1){
		printf("X gyro: %d\n", pack1);
		printf("Y gyro: %d\n", pack2);
		k_sleep(K_MSEC(500));
	}


	//package z gyro and x accel, store
	pack1 = (int16_t)(out_ev(&z)*(float)DECIMAL_SHIFT*(float)RAD_TO_DEGREE);
	
	sensor_sample_fetch_chan(dev, SENSOR_CHAN_ACCEL_XYZ);
	sensor_channel_get(dev, SENSOR_CHAN_ACCEL_X, &x);
	sensor_channel_get(dev, SENSOR_CHAN_ACCEL_Y, &y);
	sensor_channel_get(dev, SENSOR_CHAN_ACCEL_Z, &z);

	if (TESTING_MODE == 1){
		printf("Raw accel X: %d, %d\n", x.val1, x.val2);
    	printf("Raw accel Y: %d, %d\n", y.val1, y.val2);
    	printf("Raw accel Z: %d, %d\n", z.val1, z.val2);
		k_sleep(K_MSEC(500));
	}

	pack2 = (int16_t)(out_ev(&x)*(float)DECIMAL_SHIFT/(float)GRAVITY);
	data_to_store = pack_16bit_to_32bit(pack1, pack2);
	full = add_to_ring_buffer(&my_ring_buffer, data_to_store);

	if (TESTING_MODE == 1){
		printf("Z gyro: %d\n", pack1);
		printf("X accel: %d\n", pack2);
		k_sleep(K_MSEC(500));
	}

	//package y accel and z accel, store
	pack1 = (int16_t)(out_ev(&y)*(float)DECIMAL_SHIFT/(float)GRAVITY);
	pack2 = (int16_t)(out_ev(&z)*(float)DECIMAL_SHIFT/(float)GRAVITY);
	data_to_store = pack_16bit_to_32bit(pack1, pack2);
	full = add_to_ring_buffer(&my_ring_buffer, data_to_store);

	if (TESTING_MODE == 1){
		printf("Y accel: %d\n", pack1);
		printf("Z accel: %d\n", pack2);
		k_sleep(K_MSEC(500));
	}

}


int16_t get_adc(const struct adc_dt_spec *adc_channel, struct adc_sequence *sequence, int16_t *buf) {
    int32_t val_mv32;
    int err;

    /* STEP 5 - Read a sample from the ADC */
    err = adc_read(adc_channel->dev, sequence);
    if (err < 0) {
        printf("Could not read (%d)\n", err);
        return -1; // Return error indicator
    }

    val_mv32 = (int32_t)*buf;

    /* STEP 6 - Convert raw value to mV */
    err = adc_raw_to_millivolts_dt(adc_channel, &val_mv32);
    if (err < 0) {
        printf("Could not convert to millivolts (%d)\n", err);
        return -1; // Return error indicator
    }

    //printf("%d\n", (int16_t)val_mv32);
    return (int16_t)val_mv32;
}



int gather_data_no_adc(const struct device *dev){ //this function gets IMU data, and adds it to the larger ring buffer. It returns a 0 if the ring buffer is full
	int16_t pack1;
	int16_t pack2;
	uint32_t data_to_store;
	int full;

	pack1 = 0; //0 value tracks breaks between samples
	pack2 = get_elapsed_time_ms(); 
	
	data_to_store = pack_16bit_to_32bit(pack1, pack2);
	full = add_to_ring_buffer(&my_ring_buffer, data_to_store); 

	get_LSM6DSO_data(dev); //note that this function packs and stores values automatically
    
    if (is_ring_buffer_full(&my_ring_buffer)){
        return 0;
    }
    return 1;
}   
//functions below added for low power

static struct k_work lsm6dso_work;

// This function is safe to run outside ISR context
static void lsm6dso_work_handler(struct k_work *work)
{
	gpio_pin_interrupt_configure_dt(&int1_gpio, GPIO_INT_DISABLE);
    // const struct device *const dev = DEVICE_DT_GET_ONE(st_lsm6dso);
    // if (!device_is_ready(dev)) {
    //     printk("LSM6DSO device not ready\n");
    //     return;
    // }
	uint8_t wake_src, tap_src, status;
	lsm6dso_read_reg(0x1B, &wake_src);
	lsm6dso_read_reg(0x1C, &tap_src);
	lsm6dso_read_reg(0x1E, &status);
    printk("Wake-up SRC: 0x%02X\n", wake_src);
    printk("callback triggered.\n");

    //fetch_and_display(dev);  // Whatever your normal logic is
	k_sleep(K_MSEC(1000));  
	gpio_pin_interrupt_configure_dt(&int1_gpio, GPIO_INT_EDGE_TO_ACTIVE);
}

static void lsm6dso_int1_callback(const struct device *port, struct gpio_callback *cb, uint32_t pins)
{
	k_work_submit(&lsm6dso_work);
}

static void setup_int1_gpio(void)
{
    
	//gpio_pin_configure_dt(&int1_gpio, GPIO_INPUT | GPIO_PULL_UP);
	nrf_gpio_cfg_sense_input(int1_gpio.pin, NRF_GPIO_PIN_PULLUP, NRF_GPIO_PIN_SENSE_LOW);
    gpio_pin_interrupt_configure_dt(&int1_gpio, GPIO_INT_EDGE_TO_ACTIVE);
    gpio_init_callback(&int1_cb_data, lsm6dso_int1_callback, BIT(int1_gpio.pin));
    gpio_add_callback(int1_gpio.port, &int1_cb_data);
}

static void reset_registers(void){
	// 1. Reset device (optional but good practice)
	lsm6dso_write_reg(0x12, 0x01);  // CTRL3_C: SW_RESET
	k_sleep(K_MSEC(100));            // Delay to allow reset

	// 2. Disable all interrupts on INT1 and INT2
	lsm6dso_write_reg(0x5E, 0x00);  // MD1_CFG: no interrupt routed
	lsm6dso_write_reg(0x5F, 0x00);  // MD2_CFG: no interrupt routed

	// 3. Disable embedded functions, just basic accelerometer on 104 Hz, ±2g
	lsm6dso_write_reg(0x10, 0x40);  // CTRL1_XL: 104 Hz, ±2g
	lsm6dso_write_reg(0x11, 0x00);  // CTRL2_G: gyroscope off
	lsm6dso_write_reg(0x12, 0x44);  // CTRL3_C: BDU + auto-increment enabled

	// 4. Disable embedded functions access
	lsm6dso_write_reg(0x19, 0x00);  // FUNC_CFG_ACCESS: disable

	// 5. Read INT1 pin voltage level with logic analyzer or voltmeter

}

static void lsm6dso_config_motion_interrupt(void)
{
	reset_registers();
	// 1. Enable BDU and auto-increment
	lsm6dso_write_reg(0x12, 0x44);  // CTRL3_C

	// 2. Enable accelerometer: ODR = 104 Hz, FS = ±4g
	lsm6dso_write_reg(0x10, 0x50);  // CTRL1_XL

	// 3. Enable access to embedded functions
	lsm6dso_write_reg(0x01A, 0x80); // FUNC_CFG_ACCESS = enable embedded reg access

	// 4. Enable embedded functions
	lsm6dso_write_reg(0x04, 0x01);  // EMB_FUNC_EN_A = enable wake-up
	lsm6dso_write_reg(0x05, 0x00);  // EMB_FUNC_EN_B = (optional)

	// 5. Enable embedded function interrupt
	lsm6dso_write_reg(0x58, 0x80);  // TAP_CFG0: enable interrupts
	lsm6dso_write_reg(0x59, 0x0C);  // TAP_CFG2: route wake-up to INTs

	// 6. Set wake-up threshold and duration
	lsm6dso_write_reg(0x5B, 0x02);  // WAKE_UP_THS = ~2g
	lsm6dso_write_reg(0x5C, 0x00);  // WAKE_UP_DUR = min duration

	// 7. Route wake-up interrupt to INT2
	lsm6dso_write_reg(0x5F, 0x20);  // MD2_CFG: bit 5 = wake-up INT2
	// 7b. Route core wake-up interrupt to INT2 (not just embedded wake-up)
	//lsm6dso_write_reg(0x5E, 0x20);
	//lsm6dso_write_reg(0x0F, 0x20);  // INT2_CTRL: Wake-up to INT2


	// 8. (Optional) Enable HPF for reliable wake-up
	lsm6dso_write_reg(0x17, 0x09);  // CTRL8_XL: no HPF

	// 9. Exit embedded access mode
	lsm6dso_write_reg(0x1A, 0x00);  // FUNC_CFG_ACCESS = user bank

	// 10. Enable Wake-Up in CTRL10_C
	lsm6dso_write_reg(0x19, 0x24);  // CTRL10_C: FUNC_EN | WAKE_EN

	// 11. Configure INT2: push-pull, active high
	lsm6dso_write_reg(0x13, 0x00);  // CTRL4_C: default push-pull

	// 12. Enable interrupt latch
	lsm6dso_write_reg(0x0B, 0x40);  // CTRL6_C: LIR = 1

	// Explicitly disable wake-up on INT1
	lsm6dso_write_reg(0x5E, 0x00);  // MD1_CFG: clear wake-up routing on INT1

	// Route wake-up interrupt to INT2
	lsm6dso_write_reg(0x5F, 0x20);  // MD2_CFG: wake-up INT2

	// Explicitly route wake-up interrupt on INT2 control register
	lsm6dso_write_reg(0x0F, 0x20);  // INT2_CTRL: wake-up interrupt to INT2

	// Disable wake-up on INT1 control register
	lsm6dso_write_reg(0x0E, 0x00);  // INT1_CTRL

	// Optional: configure INT2 pin type
	lsm6dso_write_reg(0x13, 0x00);  // or try 0x02 for open-drain

	//enable int1 code below
	// Disable INT2
	lsm6dso_write_reg(0x5F, 0x00);  // MD2_CFG
	lsm6dso_write_reg(0x0F, 0x00);  // INT2_CTRL

	// Enable INT1 for wake-up
	lsm6dso_write_reg(0x5E, 0x20);  // MD1_CFG: route wake-up to INT1
	lsm6dso_write_reg(0x0E, 0x20);  // INT1_CTRL: route core wake-up to INT1

	// Enable full accelerometer (e.g., 104 Hz) and gyroscope (e.g., 104 Hz)
	//lsm6dso_write_reg(0x11, 0x40); // CTRL2_G = 0x40 for 104 Hz
	//lsm6dso_write_reg(0x10, 0x40); // CTRL1_XL = 0x40 for 104 Hz


}

static void powerup(void){
	k_msleep(3000); 
	lsm6dso_write_reg(0x11, 0x20);  // CTRL2_G: enable gyro at 26 Hz
	k_msleep(10);  // small delay for internal clocks to stabilize
	k_work_init(&lsm6dso_work, lsm6dso_work_handler);
}

static void int_setup(void){
	lsm6dso_config_motion_interrupt();  // <--- manually configure 2g motion INT
	k_msleep(100); 
	setup_int1_gpio();
}
static void powerdown_prep(void){
	bt_disable();
	//disable uart
	const struct device *uart_dev = device_get_binding("UART_0");
	if (uart_dev) {
		uart_irq_rx_disable(uart_dev);
		uart_irq_tx_disable(uart_dev);
	}
	//disable gpio
	// for (int pin = 0; pin < 32; pin++) {
	// 	if (pin == 15 || pin == 19 || pin == 20) {
	// 		continue;  // don't touch interrupt pin
	// 	}
	// 	nrf_gpio_cfg_input(pin, NRF_GPIO_PIN_PULLDOWN);
	// }
	
}

static void powerdown(){
	int_setup();
	powerdown_prep();
	lsm6dso_write_reg(0x11, 0x00);  // CTRL2_G = 0x00 disables gyro
	lsm6dso_write_reg(0x10, 0x58);  // CTRL1_XL: ODR=52Hz, FS=±4g
	k_msleep(50);
	nrf_power_system_off(NRF_POWER); 
	printk("This should NEVER print!\n");
}
//functions above added for low power

//this function takes a ring buffer as an input, and extracts two values from it which it then sends over bluetooth
//note that this is one of the functions that takes a ring buffer input, so sometimes it operates on data from the large ring buffer and sometimes the adc ring buffer
int send_data(struct ring_buf *rb) { 
    uint32_t buffer_value;
    int full;
    int16_t extract1;
    int16_t extract2;
    int send_success = 0; // Flag to track if both sends succeed

    // Get data from the buffer
    full = get_from_ring_buffer(rb, &buffer_value);
    extract1 = extract_first_16bit(buffer_value);
    extract2 = extract_second_16bit(buffer_value);

	//the lines below are a fix that convert to a string before sending
	char buffer1[10];  // Enough space for "-32768" and null terminator
	char buffer2[10];  // Enough space for "-32768" and null terminator
	snprintf(buffer1, sizeof(buffer1), "%d\n", extract1);
	snprintf(buffer2, sizeof(buffer2), "%d\n", extract2);

	int counter = 0;
    while (1) {
        // Check if Bluetooth is connected
        if (!is_bt_connected()) {
            printf("Bluetooth not connected. Waiting for connection...\n");
            k_sleep(K_MSEC(3000)); // Wait for 1 second before checking again
			counter++;
			if (counter==1){
				printf("Waited too long, powering down.\n");
				break;
			}
            continue; // Skip the sending attempt until Bluetooth is connected
        }

        // Attempt to send the first part of the data
        //if (bt_nus_send(NULL, (uint8_t *)&extract1, sizeof(extract1))) {
		if (bt_nus_send(NULL, (uint8_t *)buffer1, strlen(buffer1))){
            //printf("Failed to send first part of data over BLE connection\n");
        } else {
            send_success |= 1; // Mark the first send as successful
        }

        // Attempt to send the second part of the data
        //if (bt_nus_send(NULL, (uint8_t *)&extract2, sizeof(extract2))) {
		if (bt_nus_send(NULL, (uint8_t *)buffer2, strlen(buffer2))){
            printf("Failed to send data.. Please make sure your device is ready to receive BLE.\n");
        } else {
            send_success |= 2; // Mark the second send as successful
        }

        // If both parts were successfully sent, break the loop
        if (send_success == 3) {
            break;
        }

        // If any part failed, retry after waiting for 1 second
        k_sleep(K_MSEC(3000));
    }
	return counter;
}

int store_adc_data(int16_t adc1, int16_t adc2, int16_t adc3){ //this function takes three inputs, which it stores as well as the time at which the function is called
	int16_t time;
	uint32_t packed;
	int err;

	time = get_elapsed_time_ms();
	printf("Time: %d\n",time);

	packed = pack_16bit_to_32bit(time, adc1);
	err = add_to_ring_buffer(&adc_ring_buffer, packed);
	if (err == 0){
		return err;
	}
	packed = pack_16bit_to_32bit(adc2, adc3);
	err = add_to_ring_buffer(&adc_ring_buffer, packed);
	return err;
}

static void reset_sensor(){
	i2c_recover_bus(i2c_dev);
	reset_registers();
}


//main function here, this is what calls other functions and runs code.
//***************************************************************************************************
int main(void){
	ring_buf_reset(&my_ring_buffer);
	ring_buf_reset(&adc_ring_buffer);

    //all necessary initialization here
	int err = 0;
	uint8_t last_printed_percent;
	int sensor_ready = 1;
	int16_t adc1;
	int16_t adc2;
	int16_t adc3;
	const char* msg;
	
	configure_gpio();

	err = uart_init();
	if (err) {
		error();
	}

	if (IS_ENABLED(CONFIG_BT_NUS_SECURITY_ENABLED)) {
		err = bt_conn_auth_cb_register(&conn_auth_callbacks);
		if (err) {
			printk("Failed to register authorization callbacks.\n");
			return 0;
		}

		err = bt_conn_auth_info_cb_register(&conn_auth_info_callbacks);
		if (err) {
			printk("Failed to register authorization info callbacks.\n");
			return 0;
		}
	}

	err = bt_enable(NULL);
	if (err) {
		error();
	}

	//LOG_INF("Bluetooth initialized");

	k_sem_give(&ble_init_ok);

	if (IS_ENABLED(CONFIG_SETTINGS)) {
		settings_load();
	}

	err = bt_nus_init(&nus_cb);
	if (err) {
		printf("Failed to initialize UART service (err: %d)", err);
		return 0;
	}

	err = bt_le_adv_start(BT_LE_ADV_CONN, ad, ARRAY_SIZE(ad), sd,
			      ARRAY_SIZE(sd));
	if (err) {
		printf("Advertising failed to start (err %d)", err);
		return 0;
	}

	//add sensor code below
	reset_sensor();


	while (sensor_ready == 1){
		const struct device *const dev = DEVICE_DT_GET_ONE(st_lsm6dso);

		if (!device_is_ready(dev)) {
			printf("I2C device not ready.\n");
			k_msleep(3000);
		} else {
			printf("I2C device is ready!\n");
			sensor_ready = 0;
		}

		sensor_ready = set_sampling_freq(dev);
	}
	const struct device *const dev = DEVICE_DT_GET_ONE(st_lsm6dso);
	//sensor code above

	/* Define three ADC channels */
	static const struct adc_dt_spec adc_channel1 = ADC_DT_SPEC_GET_BY_IDX(DT_PATH(zephyr_user), 0);
	static const struct adc_dt_spec adc_channel2 = ADC_DT_SPEC_GET_BY_IDX(DT_PATH(zephyr_user), 1);
	static const struct adc_dt_spec adc_channel3 = ADC_DT_SPEC_GET_BY_IDX(DT_PATH(zephyr_user), 2);

	/* Define three buffers */
	int16_t buf1, buf2, buf3;

	/* Define three ADC sequences */
	struct adc_sequence sequence1 = { .buffer = &buf1, .buffer_size = sizeof(buf1) };
	struct adc_sequence sequence2 = { .buffer = &buf2, .buffer_size = sizeof(buf2) };
	struct adc_sequence sequence3 = { .buffer = &buf3, .buffer_size = sizeof(buf3) };

	//uint32_t count = 0;

	/* Check which ADC devices are ready and initialize only those */
	// Note that I think this code is unnecessary, and always sets up the channels. However, I don't want to risk removing it.
	if (adc_is_ready_dt(&adc_channel1)) {
		err = adc_channel_setup_dt(&adc_channel1);
		if (err < 0) {
			printf("Could not setup channel 1 (%d)\n", err);
		} else {
			err = adc_sequence_init_dt(&adc_channel1, &sequence1);
			if (err < 0) {
				printf("Could not initialize sequence 1\n");
			}
		}
	} else {
		printf("ADC1 not ready\n");
	}

	if (adc_is_ready_dt(&adc_channel2)) {
		err = adc_channel_setup_dt(&adc_channel2);
		if (err < 0) {
			printf("Could not setup channel 2 (%d)\n", err);
		} else {
			err = adc_sequence_init_dt(&adc_channel2, &sequence2);
			if (err < 0) {
				printf("Could not initialize sequence 2\n");
			}
		}
	} else {
		printf("ADC2 not ready\n");
	}

	if (adc_is_ready_dt(&adc_channel3)) {
		err = adc_channel_setup_dt(&adc_channel3);
		if (err < 0) {
			printf("Could not setup channel 3 (%d)\n", err);
		} else {
			err = adc_sequence_init_dt(&adc_channel3, &sequence3);
			if (err < 0) {
				printf("Could not initialize sequence 3\n");
			}
		}
	} else {
		printf("ADC3 not ready\n");
	}


	//ADC initialization above ===================================================================================================================================

	powerup();
	int powercheck;
	//more powerup stuff above

    if (ACTIVE_MODE == 1){ //if the device is in its fully active mode, recording and sending data over bluetooth
        int BLUETOOTH_MODE = 0; //assume storage starts empty
        for (;;){ //infinite loop
            if (BLUETOOTH_MODE == 0){ //function occurs if storage has just been emptied (or starts empty)
				reset_time_reference();
				while (gather_data_no_adc(dev)){
                //while (gather_data(dev, &adc_channel, &sequence, &buf)){ //goes until buffer is filled
					check_ring_buffer_progress(BUFFER_SIZE);
					k_sleep(K_MSEC(10)); //pause for 10ms
					static int counter = 0;
					
					if (++counter % 100 == 0) { // Code to run every 100th call
						adc1 = get_adc(&adc_channel1, &sequence1, &buf1);
						adc2 = get_adc(&adc_channel2, &sequence2, &buf2);
						adc3 = get_adc(&adc_channel3, &sequence3, &buf3);
						err = store_adc_data(adc1, adc2, adc3);
						if (err == 0){
							printf("ADC data could not be stored.\n");
						}
					}
					
                }
				printf("Ring buffer is full. Ready to send data over Bluetooth.\n");
                BLUETOOTH_MODE = 1;
            }
                

            if (BLUETOOTH_MODE == 1){ //function occurs once storage is full and ready to send data 
                while (!is_ring_buffer_empty(&my_ring_buffer)){ //this line starts a loop that sends all imu data over bluetooth
                    powercheck = send_data(&my_ring_buffer);
					if (powercheck > 0){
						powerdown();
					}
					check_ring_buffer_progress(BUFFER_SIZE);
                }
				printf("Ring buffer is empty. Sending ADC data now.\n");
				msg = "Sending ADC data\n";
				bt_nus_send(NULL, (uint8_t *)msg, strlen(msg));
				while (!is_ring_buffer_empty(&adc_ring_buffer)){  //this line sends ADC data over bluetooth
                    send_data(&adc_ring_buffer);
                }
                BLUETOOTH_MODE = 0; //change back to data collection mode once all data is sent
				last_printed_percent = 0; //reset buffer storage tracker
				printf("All data sent. Powering down\n");
				msg = "All data sent: Powering down.\n";
				bt_nus_send(NULL, (uint8_t *)msg, strlen(msg));
				//k_sleep(K_MSEC(20000));
				powerdown();
            }
            

        }
    }

    if (ACTIVE_MODE == 0){ //this situation would occur if we didn't want the device to be active. Likely, this mode would be to test something, perhaps to print the data to console
        
    }
}
    

Devicetree overlay:

/*
 * Copyright (c) 2022 Nordic Semiconductor ASA
 *
 * SPDX-License-Identifier: LicenseRef-Nordic-5-Clause
 */

/ {
    chosen {
        nordic,nus-uart = &uart0;
    };
};
//lines after this added for sensor
// arduino_i2c: &i2c0 {
//  lsm6dso@6b {
//      compatible = "st,lsm6dso";
//      label = "LSM6DSO";
//      reg = <0x6b>;
//  };
// };

//two blocks below this testing
&i2c0 {
    lsm6dso: lsm6dso@6b {
        compatible = "st,lsm6dso";
        reg = <0x6b>;
        label = "LSM6DSO";
        irq-gpios = <&gpio0 15 GPIO_ACTIVE_HIGH>;
        int-pin = <1>;
        status = "okay";
    };
};

&{/aliases} {
    lsm6dso-int1 = &lsm6dso;
};

// / {
//  zephyr,user {
//      io-channels = <&adc 0>;
//  };
// };

// &adc {
//  #address-cells = <1>;
//  #size-cells = <0>;
//  status = "okay";
//  channel@0 {
//      reg = <0>;
//      zephyr,gain = "ADC_GAIN_1_6";
//      zephyr,reference = "ADC_REF_INTERNAL";
//      zephyr,acquisition-time = <ADC_ACQ_TIME_DEFAULT>;
//      zephyr,input-positive = <NRF_SAADC_AIN0>; /* P0.02 for nRF52xx, P0.04 for nRF53xx */
//      zephyr,resolution = <12>;
//  };
// };

/ {
    zephyr,user {
        io-channels = <&adc 0>, <&adc 1>, <&adc 2>;
    };
};

&adc {
    #address-cells = <1>;
    #size-cells = <0>;
    status = "okay";

    channel@0 {
        reg = <0>;
        zephyr,gain = "ADC_GAIN_1_6";
        zephyr,reference = "ADC_REF_INTERNAL";
        zephyr,acquisition-time = <ADC_ACQ_TIME_DEFAULT>;
        zephyr,input-positive = <NRF_SAADC_AIN0>; /* P0.02 */
        zephyr,resolution = <12>;
    };

    channel@1 {
        reg = <1>;
        zephyr,gain = "ADC_GAIN_1_6";
        zephyr,reference = "ADC_REF_INTERNAL";
        zephyr,acquisition-time = <ADC_ACQ_TIME_DEFAULT>;
        zephyr,input-positive = <NRF_SAADC_AIN1>; /* P0.03 */
        zephyr,resolution = <12>;
    };

    channel@2 {
        reg = <2>;
        zephyr,gain = "ADC_GAIN_1_6";
        zephyr,reference = "ADC_REF_INTERNAL";
        zephyr,acquisition-time = <ADC_ACQ_TIME_DEFAULT>;
        zephyr,input-positive = <NRF_SAADC_AIN2>; /* P0.04 */
        zephyr,resolution = <12>;
    };
};
Config file:
#
# Copyright (c) 2018 Nordic Semiconductor
#
# SPDX-License-Identifier: LicenseRef-Nordic-5-Clause
#

# Enable the UART driver
CONFIG_UART_ASYNC_API=y
CONFIG_NRFX_UARTE0=y
#CONFIG_SERIAL=y

#CONFIG_GPIO=y

# Make sure printk is printing to the UART console
#CONFIG_CONSOLE=y
#CONFIG_UART_CONSOLE=y

CONFIG_HEAP_MEM_POOL_SIZE=2048

CONFIG_BT=y
CONFIG_BT_PERIPHERAL=y
CONFIG_BT_DEVICE_NAME="Hello Sangwoo"
CONFIG_BT_MAX_CONN=1
CONFIG_BT_MAX_PAIRED=1

# Enable the NUS service
CONFIG_BT_NUS=y

# Enable bonding
CONFIG_BT_SETTINGS=y
CONFIG_FLASH=y
CONFIG_FLASH_PAGE_LAYOUT=y
CONFIG_FLASH_MAP=y
CONFIG_NVS=y
CONFIG_SETTINGS=y

# Enable DK LED and Buttons library
CONFIG_DK_LIBRARY=y

# This example requires more stack
CONFIG_MAIN_STACK_SIZE=1152
CONFIG_SYSTEM_WORKQUEUE_STACK_SIZE=2048

# Config logger
CONFIG_LOG=n
#CONFIG_USE_SEGGER_RTT=y
#CONFIG_LOG_BACKEND_RTT=y
#CONFIG_LOG_BACKEND_UART=n
#CONFIG_LOG_PRINTK=n
#CONFIG_LOG_DEFAULT_LEVEL=0



CONFIG_ASSERT=y

#adding the sensor code
CONFIG_I2C=y
CONFIG_SENSOR=y
#CONFIG_LSM6DSO_TRIGGER_GLOBAL_THREAD=n
CONFIG_CBPRINTF_FP_SUPPORT=y

CONFIG_RING_BUFFER=y

CONFIG_ADC=y

#added code below
CONFIG_STDOUT_CONSOLE=y
CONFIG_GPIO=y
CONFIG_LSM6DSO=y
CONFIG_LSM6DSO_TRIGGER_GLOBAL_THREAD=y
CONFIG_CBPRINTF_FP_SUPPORT=y

# CONFIG_UART_CONSOLE=n
# CONFIG_LOG=n
# CONFIG_PRINTK=n
# CONFIG_USE_SEGGER_RTT=n
Parents
  • Hi Connors, 

    I would suggest to test with the system_off sample. 

    The current when sleeping should be around 1uA. 


    You may want to consider if you need to do SYSTEM_OFF or SYSTEM_ON Idle current is good enough. When you do system on Idle you only put the CPU to sleep not the whole system. 

    If you test with the peripheral_lbs (prj_minimal.conf) you can see the current between each BLE activity it's the system on Idle sleep current. 
    What you report of 10.5mA to 13.5 mA sounds more like both CPU and the RADIO is active which is not normal. When you do BLE the radio is active in a very short period of time. 

  • I've tried the system_off sample on my custom board with the nrf52832. It was only able to decrease to about 9.5mA, which tells me that the software side of things might not be the issue. Could this high current be due to how I'm connecting the external sensor? Right now, it's connected to VDD on the nrf52832, but maybe that's why the nrf chip can't power down properly? Would it be better to power the sensor with a GPIO pin?

Reply
  • I've tried the system_off sample on my custom board with the nrf52832. It was only able to decrease to about 9.5mA, which tells me that the software side of things might not be the issue. Could this high current be due to how I'm connecting the external sensor? Right now, it's connected to VDD on the nrf52832, but maybe that's why the nrf chip can't power down properly? Would it be better to power the sensor with a GPIO pin?

Children
Related