diff --git a/CHANGELOG b/CHANGELOG index 1f66b24..7febfc5 100644 --- a/CHANGELOG +++ b/CHANGELOG @@ -5,6 +5,11 @@ All notable changes to this project will be documented in this file. The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.1.0/), and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0.html). +## [3.3.0] + +### Added +- Low power XIAO MG24 example with BME280/BMP280 sensor, using encryption + ## [3.2.0] ## Added diff --git a/README.md b/README.md index 0f5f88e..369a09e 100644 --- a/README.md +++ b/README.md @@ -88,6 +88,7 @@ Refer to the directory `./examples` for specific library implementations. - NimBLE BLE Library [NimBLE.ino](./examples/NimBLE/NimBLE.ino) - ESP32 native IDF calls to use BLE 5 for long range and extended payload. [ESP32C6_ESP_BLE5_LongRange_Firebeetle2.ino](./examples/ESP32C6_ESP_BLE5_LongRange_Firebeetle2/ESP32C6_ESP_BLE5_LongRange_Firebeetle2.ino) - Encryption [NimBLE_Encryption.ino](./examples/NimBLE_Encryption/NimBLE_Encryption.ino) +- XIAO MG24 + BME280 temperature/pressure/humidity sensor using BLE Silabs protocol stack [XIAO_MG24.ino](./examples/XIAO_MG24/XIAO_MG24.ino) ## Usage diff --git a/examples/XIAO_MG24/XIAO_MG24.ino b/examples/XIAO_MG24/XIAO_MG24.ino new file mode 100644 index 0000000..5e774cb --- /dev/null +++ b/examples/XIAO_MG24/XIAO_MG24.ino @@ -0,0 +1,447 @@ +/* + A low power BtHome temperature/humidity/pressure sensor device with XIAO MG24 + Average current consumption is as low as 60µA! Can be even more reduced with longer sleep time. + Current during LowPower.sleep() is ~8µA including sensor (measured with BMP280, 3.3V version without level shifter). + Current during LowPower.deepSleep() would be less, but waking up from deep sleep needs a lot of energy. + So LowPower.sleep() is the better choice for this sensor with TIME_TO_SLEEP=15s. + At 60µA (with built on voltage divider), the sensor should run for more than 10 months on a 350mAh LiPo battery. + */ + +#ifndef ARDUINO_SILABS_STACK_BLE_SILABS + #error "This example is only compatible with the Silicon Labs BLE stack. Please select 'BLE (Silabs)' in 'Tools > Protocol stack'." +#endif + +#include +#include +#include +#include +// modified adc module to gain access to MG24 features like oversampling, gain or differential mode +#include "adc_mod.h" + +//----------------------------------------------------------------------------- +// Configuration switches + +#define CONF_EXTERNAL_ANTENNA 0 +#define CONF_USE_ENCRYPTION 1 +#define CONF_SERIAL_DBG 0 +#define CONF_BMP280 1 +#define CONF_BUILTIN_BATT_VOLTAGE 0 + +//----------------------------------------------------------------------------- +#if CONF_BMP280 +#include +#else +#include +#endif + +//----------------------------------------------------------------------------- +// Defines + +#define ADVERTISING_DURATION_MS 100 + +#define TIME_TO_SLEEP 15 /* Time to sleep (in seconds) */ +#define TIME_TO_SLEEP_LOW (30*60) /* Time to sleep when voltage is low (in seconds) */ + +#define LOW_VOLTAGE 3.5 /* Threshold for longer sleep time */ + +// I prefer not to transfer names +// When using encryption, space is limited +// BTHome will use part of MAC address for identification, that's fine for me +#define BTHOME_SHORT_NAME "" +#define BTHOME_COMPLETE_NAME "" + +#if !CONF_BUILTIN_BATT_VOLTAGE +#define BATT_PIN PC0 +#define R1 6.2e6f +#define R2 1.5e6f +#endif + +// XIAO MG24 pins +// on board antenna switch +#define RF_SW_PWR_PIN PB5 +#define RF_SW_SEL_PIN PB4 + +// on board Flash SPI_1 pins +#define CS1 PA6 // (21) +#define CLK1 PA0 // (17), D17 +#define MOSI1 PB0 // (15), D15 +#define MISO1 PB1 // (16), D16 + +// on board peripherals pins +#define VBAT_EN PD3 // (25) + +// Flash commands +#define READ_DATA 0x03 +#define WRITE_ENABLE 0x06 +#define PAGE_PROGRAM 0x02 +#define SECTOR_ERASE 0x20 + +//----------------------------------------------------------------------------- +// Global variables + +#if CONF_BMP280 +// Bosch BMP280 connected via I2C +Adafruit_BMP280 bmx; +#else +// Bosch BME280 connected via I2C +Adafruit_BME280 bmx; +#endif + +#if CONF_USE_ENCRYPTION +// Bind key: aab3147d9822c05fe14a0c3b77d68e55 +const uint8_t key[16] = { + 0xAA, 0xB3, 0x14, 0x7D, 0x98, 0x22, 0xC0, 0x5F, + 0xE1, 0x4A, 0x0C, 0x3B, 0x77, 0xD6, 0x8E, 0x55 +}; +bd_addr bleAddress; +#endif + +bool bleReady = false; + +BtHomeV2Device *pBtHomeV2Device; +uint32_t counter = 0; +float temperature = 0; +float airpressure = 0; +#if !CONF_BMP280 +float humidity = 0; +#endif +float voltage = 0; + +//----------------------------------------------------------------------------- + +void setup() +{ +#if CONF_SERIAL_DBG + //Initialize serial and wait for port to open: + Serial.begin(115200); + while (!Serial) { + ; // wait for serial port to connect. Needed for native USB + } +#endif + + // XIAO Settings + // On board flash + pinMode(CS1, OUTPUT); + pinMode(CLK1, OUTPUT); + pinMode(MOSI1, OUTPUT); + pinMode(MISO1, INPUT); + digitalWrite(CS1, HIGH); // CS1 HIGH + + // Flash Deep Power Down + writeEnable(); + digitalWrite(CS1, LOW); + sendSPI(0xB9); + digitalWrite(CS1, HIGH); + + // Disable JTAG debug interface, see ERF32xG24 reference manual page 903 + // reduces current while sleeping from 82µA to 7.6µA (!) + GPIO->DBGROUTEPEN = 0; + + // Switch on board LED on + pinMode(LED_BUILTIN, OUTPUT); + digitalWrite(LED_BUILTIN, LOW); + + if (!setup_bmx(true)) { +#if CONF_SERIAL_DBG + Serial.println("Could not find a valid BME280 sensor, check wiring!"); +#endif + } + + // Switch on board LED off + digitalWrite(LED_BUILTIN, HIGH); + + // Turn antenna switch supply off + pinMode(RF_SW_PWR_PIN, OUTPUT); + digitalWrite(RF_SW_PWR_PIN, LOW); + // Select chip antenna for now + pinMode(RF_SW_SEL_PIN, OUTPUT); + digitalWrite(RF_SW_SEL_PIN, LOW); + + // Output for supply voltage divider + pinMode(VBAT_EN, OUTPUT); + digitalWrite(VBAT_EN, LOW); + + // Wait until BLE subsystem is ready + while (!bleReady) { + LowPower.sleep(10); + } +#if CONF_USE_ENCRYPTION + pBtHomeV2Device = new BtHomeV2Device(BTHOME_SHORT_NAME, BTHOME_COMPLETE_NAME, false, key, bleAddress.addr); +#else + pBtHomeV2Device = new BtHomeV2Device(BTHOME_SHORT_NAME, BTHOME_COMPLETE_NAME, false); +#endif + ADC_MOD.set_read_resolution(16); +} + +//----------------------------------------------------------------------------- + +void loop(void) +{ + measurements(); + + activateAntenna(); + + prepareBtPacket1(); + ble_advertise(); + + prepareBtPacket2(); + ble_advertise(); + + deactivateAntenna(); + + if (voltage < LOW_VOLTAGE) { + LowPower.sleep(TIME_TO_SLEEP_LOW * 1000); + } else { + LowPower.sleep(TIME_TO_SLEEP * 1000); + } +} + +//----------------------------------------------------------------------------- +// Read BME280 and supply voltage + +void measurements(void) +{ + bmx.takeForcedMeasurement(); + temperature = bmx.readTemperature(); + // we want hPa, not mBar + airpressure = bmx.readPressure() * 0.01f; +#if !CONF_BMP280 + humidity = bmx.readHumidity(); +#endif + +#if CONF_BUILTIN_BATT_VOLTAGE + // activate on board voltage divider + digitalWrite(VBAT_EN, HIGH); + // wait a bit for voltage divider to settle + LowPower.sleep(10); + // read supply voltage, 1210mV reference, voltage divider by 2, gain 0.5, 16 bits resolution, 64x oversampling + // (1210mV reference is much more stable than 3V3 reference) + voltage = ADC_MOD.get_sample(PD4, PIN_NAME_NC, AR_INTERNAL1V2, iadcCfgAnalogGain0P5x, iadcCfgOsrHighSpeed64x) + * (4.0f * 0.001f * ADC_MOD.get_reference_voltage_mv() / ((1L << ADC_MOD.get_read_resolution()) - 1)); + // deactivate on board voltage divider + digitalWrite(VBAT_EN, LOW); +#else + // read supply voltage, 1210mV reference, voltage divider R1=6M2 R2=1M5, gain 1.0, 16 bits resolution, 64x oversampling + voltage = ADC_MOD.get_sample(BATT_PIN, PIN_NAME_NC, AR_INTERNAL1V2, iadcCfgAnalogGain1x, iadcCfgOsrHighSpeed64x) + * (0.001f * ADC_MOD.get_reference_voltage_mv() * (1.0f + R1/R2) / ((1L << ADC_MOD.get_read_resolution()) - 1)); +#endif + +#if CONF_SERIAL_DBG + Serial.print("Temperature = "); + Serial.print(temperature); + Serial.println(" *C"); + + Serial.print("Pressure = "); + Serial.print(airpressure); + Serial.println(" hPa"); + +#if !CONF_BMP280 + Serial.print("Humidity = "); + Serial.print(humidity); + Serial.println(" %"); +#endif + + Serial.print("Voltage = "); + Serial.print(voltage); + Serial.println(" V"); + + Serial.println("----------------------"); +#endif +} + +//----------------------------------------------------------------------------- +// BtHome Packet1 + +void prepareBtPacket1(void) +{ + pBtHomeV2Device->clearMeasurementData(); + // Available bytes when using encryption: 11, 23 otherwise + // Remaining bytes: 11 + counter += 1; + // Send a counter value to Home Assistant, can be use for i.e. packet loss statistics + pBtHomeV2Device->addCount_0_4294967295(counter); + // Remaining bytes: 6 + pBtHomeV2Device->addVoltage_0_to_65_resolution_0_001(voltage); + // Remaining bytes: 3 + pBtHomeV2Device->addTemperature_neg327_to_327_Resolution_0_01(temperature); + // Remaining bytes: 0 +} + +//----------------------------------------------------------------------------- +// BtHome Packet2 + +void prepareBtPacket2(void) +{ + pBtHomeV2Device->clearMeasurementData(); + // Available bytes when using encryption: 11, 23 otherwise +#if !CONF_BMP280 + // Remaining bytes: 11 + pBtHomeV2Device->addHumidityPercent_Resolution_0_01(humidity); +#endif + // Remaining bytes: 7 + pBtHomeV2Device->addPressureHpa(airpressure); + // Remaining bytes: 3 +} + +/**************************************************************************//** + * Starts BLE advertisement + * Initializes advertising if it's called for the first time + *****************************************************************************/ +void ble_advertise() +{ + // set up the buffer for the advertisement data + uint8_t advertisementData[MAX_ADVERTISEMENT_SIZE]; + uint8_t size = 0; + uint8_t advertising_set_handle = 0xff; + sl_status_t sc; + + // Switch on board LED on while advertising + digitalWrite(LED_BUILTIN, LOW); + + size = pBtHomeV2Device->getAdvertisementData(advertisementData); + + sc = sl_bt_advertiser_create_set(&advertising_set_handle); + app_assert_status(sc); + + // Set advertising interval to 20ms + sc = sl_bt_advertiser_set_timing( + advertising_set_handle, + 32, // minimum advertisement interval (milliseconds * 1.6) 32=20ms 80=50ms 160=100ms + 33, // maximum advertisement interval (milliseconds * 1.6) + 0, // advertisement duration, 0 = until stopped + 0); // maximum number of advertisement events, 0 = endless + app_assert_status(sc); + + // Generate data for advertising + sc = sl_bt_legacy_advertiser_set_data(advertising_set_handle, sl_bt_advertiser_advertising_data_packet, size, advertisementData); + app_assert_status(sc); + + // Start advertising and enable connections + sc = sl_bt_legacy_advertiser_start(advertising_set_handle, sl_bt_legacy_advertiser_non_connectable); + app_assert_status(sc); + +#if CONF_SERIAL_DBG + Serial.println("Raw advertising started!"); +#endif + LowPower.sleep(ADVERTISING_DURATION_MS); + + sc = sl_bt_advertiser_stop(advertising_set_handle); + app_assert_status(sc); + + sc = sl_bt_advertiser_delete_set(advertising_set_handle); + app_assert_status(sc); + +#if CONF_SERIAL_DBG + Serial.println("Raw advertising ended!"); +#endif + // Switch on board LED off + digitalWrite(LED_BUILTIN, HIGH); +} + +/**************************************************************************//** + * Bluetooth stack event handler + * Called when an event happens on BLE the stack + * + * @param[in] evt Event coming from the Bluetooth stack + *****************************************************************************/ +void sl_bt_on_event(sl_bt_msg_t *evt) +{ + sl_status_t sc = SL_STATUS_OK; + uint8_t bleAddressType; + + switch (SL_BT_MSG_ID(evt->header)) { + // This event is received when the BLE device has successfully booted + case sl_bt_evt_system_boot_id: + // Get BLE address and address type + sc = sl_bt_system_get_identity_address(&bleAddress, &bleAddressType); + app_assert_status(sc); + bleReady = true; + break; + + // Default event handler + default: +#if CONF_SERIAL_DBG + Serial.print("BLE event: "); + Serial.println(SL_BT_MSG_ID(evt->header)); +#endif + break; + } +} + +//----------------------------------------------------------------------------- +// Flash functions +void sendSPI(byte data) +{ + for (int i = 0; i < 8; i++) + { + digitalWrite(MOSI1, data & 0x80); + data <<= 1; + digitalWrite(CLK1, HIGH); + delayMicroseconds(1); + digitalWrite(CLK1, LOW); + delayMicroseconds(1); + } +} + +void writeEnable() +{ + digitalWrite(CS1, LOW); + sendSPI(WRITE_ENABLE); + digitalWrite(CS1, HIGH); +} + +//----------------------------------------------------------------------------- +// BME280/BMP280 functions + +bool setup_bmx(bool altAddress) +{ + +#if CONF_BMP280 + // default settings + // (you can also pass in a Wire library object like &Wire2) + bool bmxOk = bmx.begin(altAddress ? BMP280_ADDRESS_ALT : BMP280_ADDRESS); +#else + // default settings + // (you can also pass in a Wire library object like &Wire2) + bool bmxOk = bmx.begin(altAddress ? BME280_ADDRESS_ALTERNATE : BME280_ADDRESS); +#endif + if (!bmxOk) { + return false; + } +#if CONF_BMP280 + bmx.setSampling(Adafruit_BMP280::MODE_FORCED, /* Operating Mode. */ + Adafruit_BMP280::SAMPLING_X1, /* Temp. oversampling */ + Adafruit_BMP280::SAMPLING_X1, /* Pressure oversampling */ + Adafruit_BMP280::FILTER_OFF, /* Filtering. */ + Adafruit_BMP280::STANDBY_MS_1); /* Standby time. */ +#else + bmx.setSampling(Adafruit_BME280::MODE_FORCED, /* Operating Mode. */ + Adafruit_BME280::SAMPLING_X1, /* Temp. oversampling */ + Adafruit_BME280::SAMPLING_X1, /* Pressure oversampling */ + Adafruit_BME280::SAMPLING_X1, /* Humidity oversampling */ + Adafruit_BME280::FILTER_OFF, /* Filtering. */ + Adafruit_BME280::STANDBY_MS_0_5); /* Standby time. */ +#endif + return true; +} +//----------------------------------------------------------------------------- +// On board antenna + +void activateAntenna(void) +{ + // turn on supply for antenna switch + digitalWrite(RF_SW_PWR_PIN, HIGH); + // HIGH -> Use external antenna / LOW -> Use built-in chip antenna +#if CONF_EXTERNAL_ANTENNA + digitalWrite(RF_SW_SEL_PIN, HIGH); +#else + digitalWrite(RF_SW_SEL_PIN, LOW); +#endif +} + +void deactivateAntenna(void) +{ + // turn off supply for antenna switch + digitalWrite(RF_SW_SEL_PIN, LOW); // RFSW sel OFF + digitalWrite(RF_SW_PWR_PIN, LOW); // RFSW Power OFF +} diff --git a/examples/XIAO_MG24/adc_mod.cpp b/examples/XIAO_MG24/adc_mod.cpp new file mode 100644 index 0000000..e51f421 --- /dev/null +++ b/examples/XIAO_MG24/adc_mod.cpp @@ -0,0 +1,627 @@ +/* + * This file is part of the Silicon Labs Arduino Core + * + * The MIT License (MIT) + * + * Copyright 2024 Silicon Laboratories Inc. www.silabs.com + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "adc_mod.h" + +using namespace arduino; + +static bool dma_transfer_finished_cb(unsigned int channel, unsigned int sequenceNo, void *userParam); + +AdcClassMod::AdcClassMod() : + initialized_single(false), + initialized_scan(false), + paused_transfer(false), + current_adc_ppin(PD2), + current_adc_npin(PIN_NAME_NC), + current_adc_reference(AR_VDD), + current_read_resolution(12), + current_gain(iadcCfgAnalogGain1x), + current_osr(iadcCfgOsrHighSpeed2x), + user_onsampling_finished_callback(nullptr), + adc_mutex(nullptr) +{ + this->adc_mutex = xSemaphoreCreateMutexStatic(&this->adc_mutex_buf); + configASSERT(this->adc_mutex); +} + +void AdcClassMod::allocatePin(PinName pin) +{ + // Allocate the analog bus for ADC0 inputs + // Port C and D are handled together + // Even and odd pins on the same port have a different register value + bool pin_is_even = ((pin & 1) == 0); + if (pin >= PD0 || pin >= PC0) { + if (pin_is_even) { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDEVEN0_ADC0; + } else { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDODD0_ADC0; + } + } else if (pin >= PB0) { + if (pin_is_even) { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BEVEN0_ADC0; + } else { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BODD0_ADC0; + } + } else { + if (pin_is_even) { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AEVEN0_ADC0; + } else { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AODD0_ADC0; + } + } +} + +void AdcClassMod::init_single(PinName ppin, PinName npin, uint8_t reference, IADC_CfgAnalogGain_t gain, IADC_CfgOsrHighSpeed_t osr) +{ + if (ppin != PIN_NAME_NC) { + // Set up the positive ADC pin as an input + pinMode(ppin, INPUT); + } + if (npin != PIN_NAME_NC) { + // Set up the negative ADC pin as an input + pinMode(npin, INPUT); + } + + // Create ADC init structs with default values + IADC_Init_t init = IADC_INIT_DEFAULT; + IADC_AllConfigs_t all_configs = IADC_ALLCONFIGS_DEFAULT; + IADC_InitSingle_t init_single = IADC_INITSINGLE_DEFAULT; + IADC_SingleInput_t input = IADC_SINGLEINPUT_DEFAULT; + + // Enable IADC0, GPIO and PRS clock branches + CMU_ClockEnable(cmuClock_IADC0, true); + CMU_ClockEnable(cmuClock_GPIO, true); + CMU_ClockEnable(cmuClock_PRS, true); + + IADC_CfgReference_t sl_adc_reference; + uint32_t sl_adc_vref; + + // Set the voltage reference + if (!get_reference_info(reference, sl_adc_reference, sl_adc_vref)) { + return; + } + + all_configs.configs[0].reference = sl_adc_reference; + all_configs.configs[0].vRef = sl_adc_vref; + all_configs.configs[0].osrHighSpeed = osr; + all_configs.configs[0].analogGain = gain; + + // Reset the ADC + IADC_reset(IADC0); + + // Only configure the ADC if it is not already running + if (IADC0->CTRL == _IADC_CTRL_RESETVALUE) { + IADC_init(IADC0, &init, &all_configs); + } + + // Assign the input pin + if (ppin != PIN_NAME_NC) { + input.posInput = GPIO_to_ADC_ppin_map[ppin - PIN_NAME_MIN]; + } + if (npin != PIN_NAME_NC) { + input.negInput = GPIO_to_ADC_npin_map[npin - PIN_NAME_MIN]; + } + + init_single.alignment = iadcAlignRight16; + + // Initialize the ADC + IADC_initSingle(IADC0, &init_single, &input); + IADC_enableInt(IADC0, IADC_IEN_SINGLEDONE); + + if (ppin != PIN_NAME_NC) { + allocatePin(ppin); + } + if (npin != PIN_NAME_NC) { + allocatePin(npin); + } + + this->initialized_scan = false; + this->initialized_single = true; +} + +void AdcClassMod::init_scan(PinName pin, uint8_t reference) +{ + // Set up the ADC pin as an input + pinMode(pin, INPUT); + + // Create ADC init structs with default values + IADC_Init_t init = IADC_INIT_DEFAULT; + IADC_AllConfigs_t all_configs = IADC_ALLCONFIGS_DEFAULT; + IADC_InitScan_t init_scan = IADC_INITSCAN_DEFAULT; + + // Scan table structure + IADC_ScanTable_t scanTable = IADC_SCANTABLE_DEFAULT; + + // Enable IADC0, GPIO and PRS clock branches + CMU_ClockEnable(cmuClock_IADC0, true); + CMU_ClockEnable(cmuClock_GPIO, true); + CMU_ClockEnable(cmuClock_PRS, true); + + // Shutdown between conversions to reduce current + init.warmup = iadcWarmupNormal; + + // Set the HFSCLK prescale value here + init.srcClkPrescale = IADC_calcSrcClkPrescale(IADC0, 20000000, 0); + + IADC_CfgReference_t sl_adc_reference; + uint32_t sl_adc_vref; + + if (!get_reference_info(reference, sl_adc_reference, sl_adc_vref)) { + return; + } + + // Set the voltage reference + all_configs.configs[0].reference = sl_adc_reference; + all_configs.configs[0].vRef = sl_adc_vref; + all_configs.configs[0].osrHighSpeed = iadcCfgOsrHighSpeed2x; + all_configs.configs[0].analogGain = iadcCfgAnalogGain1x; + + /* + * CLK_SRC_ADC must be prescaled by some value greater than 1 to + * derive the intended CLK_ADC frequency. + * Based on the default 2x oversampling rate (OSRHS)... + * conversion time = ((4 * OSRHS) + 2) / fCLK_ADC + * ...which results in a maximum sampling rate of 833 ksps with the + * 2-clock input multiplexer switching time is included. + */ + all_configs.configs[0].adcClkPrescale = IADC_calcAdcClkPrescale(IADC0, + 10000000, + 0, + iadcCfgModeNormal, + init.srcClkPrescale); + + // Reset the ADC + IADC_reset(IADC0); + + // Only configure the ADC if it is not already running + if (IADC0->CTRL == _IADC_CTRL_RESETVALUE) { + IADC_init(IADC0, &init, &all_configs); + } + + // Assign the input pin + uint32_t pin_index = pin - PIN_NAME_MIN; + + // Trigger continuously once scan is started + init_scan.triggerAction = iadcTriggerActionContinuous; + // Set the SCANFIFODVL flag when scan FIFO holds 2 entries + // The interrupt associated with the SCANFIFODVL flag in the IADC_IF register is not used + init_scan.dataValidLevel = iadcFifoCfgDvl1; + // Enable DMA wake-up to save the results when the specified FIFO level is hit + init_scan.fifoDmaWakeup = true; + + scanTable.entries[0].posInput = GPIO_to_ADC_ppin_map[pin_index]; + scanTable.entries[0].includeInScan = true; + + // Initialize scan + IADC_initScan(IADC0, &init_scan, &scanTable); + IADC_enableInt(IADC0, IADC_IEN_SCANTABLEDONE); + + // Allocate the analog bus for ADC0 inputs + // Port C and D are handled together + // Even and odd pins on the same port have a different register value + bool pin_is_even = (pin % 2 == 0); + if (pin >= PD0 || pin >= PC0) { + if (pin_is_even) { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDEVEN0_ADC0; + } else { + GPIO->CDBUSALLOC |= GPIO_CDBUSALLOC_CDODD0_ADC0; + } + } else if (pin >= PB0) { + if (pin_is_even) { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BEVEN0_ADC0; + } else { + GPIO->BBUSALLOC |= GPIO_BBUSALLOC_BODD0_ADC0; + } + } else { + if (pin_is_even) { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AEVEN0_ADC0; + } else { + GPIO->ABUSALLOC |= GPIO_ABUSALLOC_AODD0_ADC0; + } + } + + this->initialized_single = false; + this->initialized_scan = true; +} + +sl_status_t AdcClassMod::init_dma(uint32_t *buffer, uint32_t size) +{ + sl_status_t status; + if (!this->initialized_scan) { + return SL_STATUS_NOT_INITIALIZED; + } + + // Initialize DMA with default parameters + DMADRV_Init(); + + // Allocate DMA channel + status = DMADRV_AllocateChannel(&this->dma_channel, NULL); + if (status != ECODE_EMDRV_DMADRV_OK) { + return SL_STATUS_FAIL; + } + + // Trigger LDMA transfer on IADC scan completion + LDMA_TransferCfg_t transferCfg = LDMA_TRANSFER_CFG_PERIPHERAL(ldmaPeripheralSignal_IADC0_IADC_SCAN); + + /* + * Set up a linked descriptor to save scan results to the + * user-specified buffer. By linking the descriptor to itself + * (the last argument is the relative jump in terms of the number of + * descriptors), transfers will run continuously. + */ + #pragma GCC diagnostic ignored "-Wmissing-field-initializers" + this->ldma_descriptor = (LDMA_Descriptor_t)LDMA_DESCRIPTOR_LINKREL_P2M_WORD(&(IADC0->SCANFIFODATA), buffer, size, 0); + + DMADRV_LdmaStartTransfer((int)this->dma_channel, &transferCfg, &this->ldma_descriptor, dma_transfer_finished_cb, NULL); + return SL_STATUS_OK; +} + +uint16_t AdcClassMod::get_sample(PinName ppin, PinName npin, uint8_t reference, IADC_CfgAnalogGain_t gain, IADC_CfgOsrHighSpeed_t osr) +{ + if (reference >= AR_MAX) { + return 0; + } + + xSemaphoreTake(this->adc_mutex, portMAX_DELAY); + + if (this->initialized_scan) { + this->scan_stop(); + } + + if (!this->initialized_single || (ppin != this->current_adc_ppin) || (npin != this->current_adc_npin) + || (reference != this->current_adc_reference) || (gain != this->current_gain) || (osr != this->current_osr)) + { + this->current_adc_ppin = ppin; + this->current_adc_npin = npin; + this->current_adc_reference = reference; + this->current_gain = gain; + this->current_osr = osr; + this->init_single(ppin, npin, reference, gain, osr); + } + // Clear single done interrupt + IADC_clearInt(IADC0, IADC_IF_SINGLEDONE); + + // Start conversion and wait for result + IADC_command(IADC0, iadcCmdStartSingle); + while (!(IADC_getInt(IADC0) & IADC_IF_SINGLEDONE)) { + yield(); + } + uint16_t result = IADC_readSingleData(IADC0); + + xSemaphoreGive(this->adc_mutex); + + // Apply the configured read resolution + result = result >> (this->max_read_resolution_bits - this->current_read_resolution); + + return result; +} + +void AdcClassMod::set_reference(uint8_t reference) +{ + if (reference >= AR_MAX || reference == this->current_adc_reference) { + return; + } + xSemaphoreTake(this->adc_mutex, portMAX_DELAY); + this->current_adc_reference = reference; + if (this->initialized_single) { + this->init_single(this->current_adc_ppin, this->current_adc_npin, this->current_adc_reference, this->current_gain, this->current_osr); + } else if (this->initialized_scan) { + this->init_scan(this->current_adc_ppin, this->current_adc_reference); + } + xSemaphoreGive(this->adc_mutex); +} + +void AdcClassMod::set_read_resolution(uint8_t resolution) +{ + if (resolution > this->max_read_resolution_bits) { + this->current_read_resolution = this->max_read_resolution_bits; + return; + } + this->current_read_resolution = resolution; +} + +uint8_t AdcClassMod::get_read_resolution(void) +{ + return this->current_read_resolution; +} + +void AdcClassMod::set_gain(IADC_CfgAnalogGain_t gain) +{ + if (gain == this->current_gain) { + return; + } + this->current_gain = gain; +} + +void AdcClassMod::set_oversampling(IADC_CfgOsrHighSpeed_t osr) +{ + if (osr == this->current_osr) { + return; + } + this->current_osr = osr; +} + +bool AdcClassMod::get_reference_info(uint8_t reference, IADC_CfgReference_t& sl_adc_reference, uint32_t& sl_adc_vref) +{ + // Set the voltage reference + switch (reference) { + case AR_INTERNAL1V2: + sl_adc_reference = iadcCfgReferenceInt1V2; + sl_adc_vref = 1210; + break; + + case AR_EXTERNAL_1V25: + sl_adc_reference = iadcCfgReferenceExt1V25; + sl_adc_vref = 1250; + break; + + case AR_VDD: + sl_adc_reference = iadcCfgReferenceVddx; + sl_adc_vref = 3300; + break; + + case AR_08VDD: + sl_adc_reference = iadcCfgReferenceVddX0P8Buf; + sl_adc_vref = 2640; + break; + + default: + return false; + } + return true; +} + +int16_t AdcClassMod::get_reference_voltage_mv(void) +{ + IADC_CfgReference_t sl_adc_reference; + uint32_t sl_adc_vref; + + if (!get_reference_info(this->current_adc_reference, sl_adc_reference, sl_adc_vref)) { + return -1; + } + return sl_adc_vref; +} + +sl_status_t AdcClassMod::scan_start(PinName pin, uint32_t *buffer, uint32_t size, void (*user_onsampling_finished_callback)()) +{ + sl_status_t status = SL_STATUS_FAIL; + xSemaphoreTake(this->adc_mutex, portMAX_DELAY); + + if ((!this->initialized_scan && !this->initialized_single) || (pin != this->current_adc_ppin)) { + // Initialize in scan mode + this->current_adc_ppin = pin; + this->user_onsampling_finished_callback = user_onsampling_finished_callback; + this->init_scan(this->current_adc_ppin, this->current_adc_reference); + status = this->init_dma(buffer, size); + } else if (this->initialized_scan && this->paused_transfer) { + // Resume DMA transfer if paused + status = DMADRV_ResumeTransfer(this->dma_channel); + this->paused_transfer = false; + } else if (this->initialized_single) { + // Initialize in scan mode if it was initialized in single mode + this->deinit(); + this->current_adc_ppin = pin; + this->user_onsampling_finished_callback = user_onsampling_finished_callback; + this->init_scan(this->current_adc_ppin, this->current_adc_reference); + status = this->init_dma(buffer, size); + } else { + xSemaphoreGive(this->adc_mutex); + return status; + } + + // Start the conversion and wait for results + IADC_command(IADC0, iadcCmdStartScan); + + xSemaphoreGive(this->adc_mutex); + return status; +} + +void AdcClassMod::scan_stop() +{ + // Pause sampling + DMADRV_PauseTransfer(this->dma_channel); + this->paused_transfer = true; +} + +void AdcClassMod::deinit() +{ + // Stop sampling + DMADRV_StopTransfer(this->dma_channel); + + // Free resources + DMADRV_FreeChannel(this->dma_channel); + + // Reset the ADC + IADC_reset(IADC0); + + this->initialized_scan = false; + this->initialized_single = false; + this->current_adc_ppin = PIN_NAME_NC; + this->current_adc_npin = PIN_NAME_NC; +} + +void AdcClassMod::handle_dma_finished_callback() +{ + if (!this->user_onsampling_finished_callback) { + return; + } + + this->user_onsampling_finished_callback(); +} + +bool dma_transfer_finished_cb(unsigned int channel, unsigned int sequenceNo, void *userParam) +{ + (void)channel; + (void)sequenceNo; + (void)userParam; + + ADC.handle_dma_finished_callback(); + return false; +} + +const IADC_PosInput_t AdcClassMod::GPIO_to_ADC_ppin_map[64] = { + // Port A + iadcPosInputPortAPin0, + iadcPosInputPortAPin1, + iadcPosInputPortAPin2, + iadcPosInputPortAPin3, + iadcPosInputPortAPin4, + iadcPosInputPortAPin5, + iadcPosInputPortAPin6, + iadcPosInputPortAPin7, + iadcPosInputPortAPin8, + iadcPosInputPortAPin9, + iadcPosInputPortAPin10, + iadcPosInputPortAPin11, + iadcPosInputPortAPin12, + iadcPosInputPortAPin13, + iadcPosInputPortAPin14, + iadcPosInputPortAPin15, + // Port B + iadcPosInputPortBPin0, + iadcPosInputPortBPin1, + iadcPosInputPortBPin2, + iadcPosInputPortBPin3, + iadcPosInputPortBPin4, + iadcPosInputPortBPin5, + iadcPosInputPortBPin6, + iadcPosInputPortBPin7, + iadcPosInputPortBPin8, + iadcPosInputPortBPin9, + iadcPosInputPortBPin10, + iadcPosInputPortBPin11, + iadcPosInputPortBPin12, + iadcPosInputPortBPin13, + iadcPosInputPortBPin14, + iadcPosInputPortBPin15, + // Port C + iadcPosInputPortCPin0, + iadcPosInputPortCPin1, + iadcPosInputPortCPin2, + iadcPosInputPortCPin3, + iadcPosInputPortCPin4, + iadcPosInputPortCPin5, + iadcPosInputPortCPin6, + iadcPosInputPortCPin7, + iadcPosInputPortCPin8, + iadcPosInputPortCPin9, + iadcPosInputPortCPin10, + iadcPosInputPortCPin11, + iadcPosInputPortCPin12, + iadcPosInputPortCPin13, + iadcPosInputPortCPin14, + iadcPosInputPortCPin15, + // Port D + iadcPosInputPortDPin0, + iadcPosInputPortDPin1, + iadcPosInputPortDPin2, + iadcPosInputPortDPin3, + iadcPosInputPortDPin4, + iadcPosInputPortDPin5, + iadcPosInputPortDPin6, + iadcPosInputPortDPin7, + iadcPosInputPortDPin8, + iadcPosInputPortDPin9, + iadcPosInputPortDPin10, + iadcPosInputPortDPin11, + iadcPosInputPortDPin12, + iadcPosInputPortDPin13, + iadcPosInputPortDPin14, + iadcPosInputPortDPin15 +}; + +const IADC_NegInput_t AdcClassMod::GPIO_to_ADC_npin_map[64] = { + // Port A + iadcNegInputPortAPin0, + iadcNegInputPortAPin1, + iadcNegInputPortAPin2, + iadcNegInputPortAPin3, + iadcNegInputPortAPin4, + iadcNegInputPortAPin5, + iadcNegInputPortAPin6, + iadcNegInputPortAPin7, + iadcNegInputPortAPin8, + iadcNegInputPortAPin9, + iadcNegInputPortAPin10, + iadcNegInputPortAPin11, + iadcNegInputPortAPin12, + iadcNegInputPortAPin13, + iadcNegInputPortAPin14, + iadcNegInputPortAPin15, + // Port B + iadcNegInputPortBPin0, + iadcNegInputPortBPin1, + iadcNegInputPortBPin2, + iadcNegInputPortBPin3, + iadcNegInputPortBPin4, + iadcNegInputPortBPin5, + iadcNegInputPortBPin6, + iadcNegInputPortBPin7, + iadcNegInputPortBPin8, + iadcNegInputPortBPin9, + iadcNegInputPortBPin10, + iadcNegInputPortBPin11, + iadcNegInputPortBPin12, + iadcNegInputPortBPin13, + iadcNegInputPortBPin14, + iadcNegInputPortBPin15, + // Port C + iadcNegInputPortCPin0, + iadcNegInputPortCPin1, + iadcNegInputPortCPin2, + iadcNegInputPortCPin3, + iadcNegInputPortCPin4, + iadcNegInputPortCPin5, + iadcNegInputPortCPin6, + iadcNegInputPortCPin7, + iadcNegInputPortCPin8, + iadcNegInputPortCPin9, + iadcNegInputPortCPin10, + iadcNegInputPortCPin11, + iadcNegInputPortCPin12, + iadcNegInputPortCPin13, + iadcNegInputPortCPin14, + iadcNegInputPortCPin15, + // Port D + iadcNegInputPortDPin0, + iadcNegInputPortDPin1, + iadcNegInputPortDPin2, + iadcNegInputPortDPin3, + iadcNegInputPortDPin4, + iadcNegInputPortDPin5, + iadcNegInputPortDPin6, + iadcNegInputPortDPin7, + iadcNegInputPortDPin8, + iadcNegInputPortDPin9, + iadcNegInputPortDPin10, + iadcNegInputPortDPin11, + iadcNegInputPortDPin12, + iadcNegInputPortDPin13, + iadcNegInputPortDPin14, + iadcNegInputPortDPin15 +}; + +arduino::AdcClassMod ADC_MOD; diff --git a/examples/XIAO_MG24/adc_mod.h b/examples/XIAO_MG24/adc_mod.h new file mode 100644 index 0000000..456db1f --- /dev/null +++ b/examples/XIAO_MG24/adc_mod.h @@ -0,0 +1,213 @@ +/* + * This file is part of the Silicon Labs Arduino Core + * + * The MIT License (MIT) + * + * Copyright 2024 Silicon Laboratories Inc. www.silabs.com + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + */ + +#include "Arduino.h" +#include "pinDefinitions.h" + +#ifndef __ARDUINO_ADC_MOD_H +#define __ARDUINO_ADC_MOD_H + +#include +#include +#include "em_cmu.h" +#include "em_iadc.h" +#include "em_ldma.h" +#include "dmadrv.h" +#include "FreeRTOS.h" +#include "semphr.h" +#include "sl_status.h" +#include "adc.h" + +namespace arduino { +class AdcClassMod { +public: + + /***************************************************************************//** + * Constructor for AdcClassMod + ******************************************************************************/ + AdcClassMod(); + + /***************************************************************************//** + * Performs a single ADC measurement on the provided pin and returns the sample + * + * @param[in] ppin The pin number of the positive ADC input + * @param[in] npin The pin number of the negative ADC input (set to PIN_NAME_NC for non differential positive mode) + * @param[in] reference The selected voltage reference from 'analog_references' + * @param[in] gain The selected gain from 'IADC_CfgAnalogGain_t' + * @param[in] osr The selected oversampling rate from 'IADC_CfgOsrHighSpeed_t' + * + * @return the measured ADC sample + ******************************************************************************/ + uint16_t get_sample(PinName ppin, PinName npin = PIN_NAME_NC, uint8_t reference = AR_VDD, + IADC_CfgAnalogGain_t gain = iadcCfgAnalogGain1x, IADC_CfgOsrHighSpeed_t osr = iadcCfgOsrHighSpeed2x); + + /***************************************************************************//** + * Sets the ADC voltage reference + * + * @param[in] reference The selected voltage reference from 'analog_references' + ******************************************************************************/ + void set_reference(uint8_t reference); + + /***************************************************************************//** + * Sets the ADC read resolution + * + * @param[in] resolution The selected read resolution in bits + ******************************************************************************/ + void set_read_resolution(uint8_t resolution); + + /***************************************************************************//** + * Starts ADC in scan (continuous) mode + * + * @param[in] buffer The buffer where the sampled data is stored + * @param[in] size The size of the buffer + * @param[in] channel The number of the LDMA channel used + * + * @return Status of the scan init process + ******************************************************************************/ + sl_status_t scan_start(PinName pin, uint32_t *buffer, uint32_t size, void (*user_onsampling_finished_callback)()); + + /***************************************************************************//** + * Stops ADC scan + ******************************************************************************/ + void scan_stop(); + + /***************************************************************************//** + * De-initialize the ADC + ******************************************************************************/ + void deinit(); + + /***************************************************************************//** + * Callback handler for the DMA transfer + ******************************************************************************/ + void handle_dma_finished_callback(); + + // The maximum read resolution of the ADC + static const uint8_t max_read_resolution_bits = 16u; + + /***************************************************************************//** + * Sets the ADC gain factor + * + * @param[in] gain The selected gain from 'IADC_CfgAnalogGain_t' + ******************************************************************************/ + void set_gain(IADC_CfgAnalogGain_t gain); + + /***************************************************************************//** + * Sets the ADC oversampling rate + * + * @param[in] osr The selected oversampling rate from 'IADC_CfgOsrHighSpeed_t' + ******************************************************************************/ + void set_oversampling(IADC_CfgOsrHighSpeed_t osr); + + /***************************************************************************//** + * Gets the ADC read resolution + * + * @return The selected read resolution in bits + ******************************************************************************/ + uint8_t get_read_resolution(void); + + /***************************************************************************//** + * Gets the voltage of the selected voltage reference in milli volts + * + * @return Voltage on milli volts + ******************************************************************************/ + int16_t get_reference_voltage_mv(void); + +protected: + /***************************************************************************//** + * Initializes the ADC hardware as single shot + * + * @param[in] ppin The pin number of the positive ADC input + * @param[in] npin The pin number of the negative ADC input + * @param[in] reference The selected voltage reference from 'analog_references' + * @param[in] gain The selected gain from 'IADC_CfgAnalogGain_t' + * @param[in] osr The selected oversampling rate from 'IADC_CfgOsrHighSpeed_t' + ******************************************************************************/ + void init_single(PinName ppin, PinName npin, uint8_t reference, IADC_CfgAnalogGain_t gain, IADC_CfgOsrHighSpeed_t osr); + + /***************************************************************************//** + * Initializes the ADC hardware in scan (continuous) mode + * + * @param[in] pin The pin number of the ADC input + ******************************************************************************/ + void init_scan(PinName pin, uint8_t reference); + + /**************************************************************************//** + * Initializes the DMA hardware + * + * @param[in] buffer Pointer to the array where ADC results will be stored + * @param[in] size Size of the array + * @param[in] channel Channel to use for transfer + * + * @return Status of the DMA init process + *****************************************************************************/ + sl_status_t init_dma(uint32_t *buffer, uint32_t size); + + /**************************************************************************//** + * Get characteristics of voltage reference + * + * @param[in] reference The voltage reference from 'analog_references' + * @param[out] sl_adc_reference Value of reference mapped to 'IADC_CfgReference_t' + * @param[out] sl_adc_vref Voltage of reference + * + * @return Status of the DMA init process + *****************************************************************************/ + bool get_reference_info(uint8_t reference, IADC_CfgReference_t& sl_adc_reference, uint32_t& sl_adc_vref); + + /**************************************************************************//** + * Allocate the analog bus for ADC0 inputs + * + * @param[in] pin The pin number of the ADC input + *****************************************************************************/ + void allocatePin(PinName pin); + + bool initialized_single; + bool initialized_scan; + bool paused_transfer; + + PinName current_adc_ppin; + PinName current_adc_npin; + uint8_t current_adc_reference; + uint8_t current_read_resolution; + IADC_CfgAnalogGain_t current_gain; + IADC_CfgOsrHighSpeed_t current_osr; + + LDMA_Descriptor_t ldma_descriptor; + unsigned int dma_channel; + unsigned int dma_sequence_number; + + void (*user_onsampling_finished_callback)(void); + + static const IADC_PosInput_t GPIO_to_ADC_ppin_map[64]; + static const IADC_NegInput_t GPIO_to_ADC_npin_map[64]; + + SemaphoreHandle_t adc_mutex; + StaticSemaphore_t adc_mutex_buf; +}; +} // namespace arduino + +extern arduino::AdcClassMod ADC_MOD; + +#endif // __ARDUINO_ADC_MOD_H diff --git a/examples/XIAO_nrf54L15/.gitignore b/examples/XIAO_nrf54L15/.gitignore new file mode 100644 index 0000000..32a0e5c --- /dev/null +++ b/examples/XIAO_nrf54L15/.gitignore @@ -0,0 +1,2 @@ +# Build directories +build/ diff --git a/examples/XIAO_nrf54L15/CMakeLists.txt b/examples/XIAO_nrf54L15/CMakeLists.txt new file mode 100644 index 0000000..88a4aaa --- /dev/null +++ b/examples/XIAO_nrf54L15/CMakeLists.txt @@ -0,0 +1,21 @@ +# +# Copyright (c) 2018 Nordic Semiconductor +# +# SPDX-License-Identifier: LicenseRef-Nordic-5-Clause +# +cmake_minimum_required(VERSION 3.20.0) + +find_package(Zephyr REQUIRED HINTS $ENV{ZEPHYR_BASE}) +project(NONE) + +# NORDIC SDK APP START +target_sources(app PRIVATE src/main.cpp) +target_sources(app PRIVATE src/adc.c) +target_sources(app PRIVATE src/bme280.c) +target_sources(app PRIVATE src/wdt.c) +target_sources(app PRIVATE ../../src/BaseDevice.cpp) +target_sources(app PRIVATE ../../src/BtHomeV2Device.cpp) + +# NORDIC SDK APP END +zephyr_library_include_directories(.) + diff --git a/examples/XIAO_nrf54L15/Kconfig.sysbuild b/examples/XIAO_nrf54L15/Kconfig.sysbuild new file mode 100644 index 0000000..d561707 --- /dev/null +++ b/examples/XIAO_nrf54L15/Kconfig.sysbuild @@ -0,0 +1,13 @@ +# +# Copyright (c) 2023 Nordic Semiconductor +# +# SPDX-License-Identifier: LicenseRef-Nordic-5-Clause +# + +source "${ZEPHYR_BASE}/share/sysbuild/Kconfig" + +config NRF_DEFAULT_IPC_RADIO + default y + +config NETCORE_IPC_RADIO_BT_HCI_IPC + default y diff --git a/examples/XIAO_nrf54L15/README.md b/examples/XIAO_nrf54L15/README.md new file mode 100644 index 0000000..07d1a56 --- /dev/null +++ b/examples/XIAO_nrf54L15/README.md @@ -0,0 +1,28 @@ +# BTHomeV2 XIAO nrf54l15 example + +Requirements: +- Setup nRFConnect SDK as described here: https://wiki.seeedstudio.com/xiao_nrf54l15_sense_getting_started/ +- In Visual Studio Code, open folder examples/XIAO_nrf54L15 +- Select nrf Connect in Activity Bar +- Select 'Add build configuration' +- Choose Board target, Base configuration files and Base Devicetree overlays, perform 'Generate and Build' + +![Home Assistant Display](./assets/buildconfig.png) + +- Connect a BME280 or BMP280 breakout board (3V3 version prefered) with XIAO nrf54l15 using standard pins +- Connect XIAO nrf54l15 via USB +- Do a 'west flash' + +The sensor should show up in Home Assistant + +What to expect? + +![Home Assistant Display](./assets/hadashboard.png) + +These sensors are solar powered by small panels with 5V or 6V. The panel charges a supercap with 1.5F (54L15) or 5F (MG24). This is a perfect setup to measure the average power consumption (or average current): MG24 ~40µA, 54L15 ~10µA. + +Packet loss is calculated with the help of a counter which increments with every sent packet: +- Setup two HA helpers statistics with max age 1h +- one with count (=packets received per hour) +- the other with change (=packets sent per hour) +- Another helper (template) with formula 1 - received_per_hour/sent_per_hour gives the packet loss percentage \ No newline at end of file diff --git a/examples/XIAO_nrf54L15/assets/buildconfig.png b/examples/XIAO_nrf54L15/assets/buildconfig.png new file mode 100644 index 0000000..dcdbb52 Binary files /dev/null and b/examples/XIAO_nrf54L15/assets/buildconfig.png differ diff --git a/examples/XIAO_nrf54L15/assets/hadashboard.png b/examples/XIAO_nrf54L15/assets/hadashboard.png new file mode 100644 index 0000000..35b811a Binary files /dev/null and b/examples/XIAO_nrf54L15/assets/hadashboard.png differ diff --git a/examples/XIAO_nrf54L15/boards/xiao_nrf54l15_nrf54l15_cpuapp.overlay b/examples/XIAO_nrf54L15/boards/xiao_nrf54l15_nrf54l15_cpuapp.overlay new file mode 100644 index 0000000..0136f89 --- /dev/null +++ b/examples/XIAO_nrf54L15/boards/xiao_nrf54l15_nrf54l15_cpuapp.overlay @@ -0,0 +1,77 @@ +/ { + zephyr,user { + io-channels = <&adc 0>, + <&adc 1>, + <&adc 2>, + <&adc 3>, + <&adc 4>, + <&adc 5>, + <&adc 6>, + <&adc 7>; + }; + bme280_pwr: bme280_pwr { + compatible = "regulator-fixed"; + regulator-name = "bme280_pwr"; + // GPIO D2 = P1.6 on the XIAO nRF54L15 + enable-gpios = <&gpio1 6 GPIO_ACTIVE_HIGH>; + }; +}; + +&wdt31 { + status = "okay"; +}; + +dmic_dev: &pdm20 { + status = "okay"; +}; + +&vbat_pwr { + /delete-property/ regulator-boot-on; +}; + +&rfsw_pwr { + /delete-property/ regulator-boot-on; +}; + +&pdm_imu_pwr{ + /delete-property/ regulator-boot-on; +}; + +&temp { + status = "disabled"; +}; + +&adc { + channel@0 { + reg = <0>; + zephyr,gain = "ADC_GAIN_2"; + zephyr,reference = "ADC_REF_INTERNAL"; + zephyr,acquisition-time = <0>; + zephyr,input-positive = ; + zephyr,input-negative = ; + zephyr,differential; + zephyr,resolution = <14>; + }; + + channel@7 { + reg = <7>; + zephyr,gain = "ADC_GAIN_1_4"; + zephyr,reference = "ADC_REF_INTERNAL"; + zephyr,acquisition-time = <0>; + zephyr,resolution = <14>; + }; +}; + +&i2c22 { + bme280@76 { + compatible = "bosch,bme280"; + reg = <0x76>; + zephyr,deferred-init; + }; + zephyr,deferred-init; +}; + +/* Board alias often points xiao_serial -> &uart21; kill it to be safe. */ +&uart21 { + status = "disabled"; +}; diff --git a/examples/XIAO_nrf54L15/prj.conf b/examples/XIAO_nrf54L15/prj.conf new file mode 100644 index 0000000..f613e90 --- /dev/null +++ b/examples/XIAO_nrf54L15/prj.conf @@ -0,0 +1,61 @@ +# +# Copyright (c) 2018 Nordic Semiconductor +# +# SPDX-License-Identifier: LicenseRef-Nordic-5-Clause +# +CONFIG_PM_DEVICE=y + +# Bluetooth LE +# STEP 1 - Include the Bluetooth LE stack in your project +CONFIG_BT=y +CONFIG_BT_PERIPHERAL=y + +# STEP 2 - Set the Bluetooth LE device name +# CONFIG_BT_DEVICE_NAME="Nordic_Beacon" +CONFIG_BT_DEVICE_NAME="NB" + +CONFIG_ADC=y +CONFIG_I2C=y +CONFIG_SENSOR=y +CONFIG_SENSOR_ASYNC_API=y +CONFIG_REGULATOR=y +CONFIG_GPIO=y +CONFIG_BME280=y +CONFIG_BME280_MODE_FORCED=y +# CONFIG_PWM=y +CONFIG_WATCHDOG=y + +CONFIG_NRFX_POWER=y +CONFIG_POWEROFF=y +CONFIG_RETAINED_MEM=y +CONFIG_STATIC_INIT_GNU=y + +CONFIG_CPP=y +CONFIG_REQUIRES_FULL_LIBCPP=y +CONFIG_BT_EAD=y + +# ========================================================= +# Serial port and console configuration +# ========================================================= +CONFIG_SERIAL=n +CONFIG_CONSOLE=y +CONFIG_UART_CONSOLE=y +CONFIG_CBPRINTF_FP_SUPPORT=y + +# ========================================================= +# Log and Debugging +# ========================================================= +CONFIG_LOG=y +CONFIG_PRINTK=y +CONFIG_LOG_PRINTK=n +CONFIG_LOG_MODE_IMMEDIATE=n +CONFIG_LOG_DEFAULT_LEVEL=3 + +# ========================================================= +# Memory and Stack +# ========================================================= +CONFIG_MAIN_STACK_SIZE=4096 +CONFIG_HEAP_MEM_POOL_SIZE=16384 +CONFIG_SYSTEM_WORKQUEUE_STACK_SIZE=4096 +# CONFIG_NEWLIB_LIBC=y +# CONFIG_NEWLIB_LIBC_FLOAT_PRINTF=y diff --git a/examples/XIAO_nrf54L15/src/adc.c b/examples/XIAO_nrf54L15/src/adc.c new file mode 100644 index 0000000..2b54e26 --- /dev/null +++ b/examples/XIAO_nrf54L15/src/adc.c @@ -0,0 +1,88 @@ + +/* + Wrapper for ADC + */ + +#include "adc.h" + +LOG_MODULE_REGISTER(SolarSensor54l15AnalogIO, LOG_LEVEL_INF); + +#define DT_SPEC_AND_COMMA(node_id, prop, idx) ADC_DT_SPEC_GET_BY_IDX(node_id, idx), + +/* Data of ADC io-channels specified in devicetree. */ +static const struct adc_dt_spec adc_channels[] = { + DT_FOREACH_PROP_ELEM(DT_PATH(zephyr_user), io_channels, DT_SPEC_AND_COMMA) +}; + +/** + * + */ +int adcSetup(uint8_t channel) +{ + int err; + + LOG_INF("channel %d gain %d", channel, adc_channels[channel].channel_cfg.gain); + + /* Configure channels individually prior to sampling. */ + if (!adc_is_ready_dt(&adc_channels[channel])) { + LOG_ERR("ADC controller device %s not ready\n", adc_channels[channel].dev->name); + return -1; + } + + err = adc_channel_setup_dt(&adc_channels[channel]); + if (err < 0) { + LOG_ERR("Could not setup channel #%d (%d)\n", channel, err); + return -1; + } + + return 0; +} + +int adcRead(int32_t *pValMV, int32_t *pRaw, uint8_t channel) +{ + int err; + uint16_t buf; + + struct adc_sequence sequence = { + .buffer = &buf, + /* buffer size in bytes, not number of samples */ + .buffer_size = sizeof(buf), + }; + + (void)adc_sequence_init_dt(&adc_channels[channel], &sequence); + + err = adc_read_dt(&adc_channels[channel], &sequence); + if (err < 0) { + LOG_ERR("Could not read (%d)\n", err); + return err; + } + + /* + * If using differential mode, the 16 bit value + * in the ADC sample buffer should be a signed 2's + * complement value. + */ + int32_t raw; + if (adc_channels[channel].channel_cfg.differential) { + raw = (int32_t)((int16_t)buf); + } else { + raw = (int32_t)buf; + } + if (pRaw != NULL) { + *pRaw = raw; + } + uint32_t tmp = raw; + if (pValMV != NULL) { + err = adc_raw_to_millivolts_dt(&adc_channels[channel], &raw); + /* conversion to mV may not be supported, skip if not */ + if (err < 0) { + LOG_ERR(" value in mV not available\n"); + return err; + } + LOG_INF("channel %d voltage = %" PRId32 " mV raw = %d\n", channel, raw, tmp); + *pValMV = raw; + } else { + LOG_INF("channel %d raw = %d\n", channel, raw); + } + return 0; +} diff --git a/examples/XIAO_nrf54L15/src/adc.h b/examples/XIAO_nrf54L15/src/adc.h new file mode 100644 index 0000000..dbd8cdd --- /dev/null +++ b/examples/XIAO_nrf54L15/src/adc.h @@ -0,0 +1,33 @@ +#pragma once +/* + Wrapper for ADC + */ + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Initialize given ADC channel + * + * @param channel index of ADC channel + * + * @retval 0 if initialization was successfull, negative value otherwise + */ +extern int adcSetup(uint8_t channel); +/** + * @brief Read value from ADC channel + * + * @param pValMV pointer to result in milli volts, may be NULL + * @param pRaw pointer to raw value, may be NULL + * + * @retval 0 if value could be read, negative value otherwise + */ +extern int adcRead(int32_t *pValMV, int32_t *pRaw, uint8_t channel); + +#ifdef __cplusplus +} +#endif diff --git a/examples/XIAO_nrf54L15/src/bme280.c b/examples/XIAO_nrf54L15/src/bme280.c new file mode 100644 index 0000000..76b9a77 --- /dev/null +++ b/examples/XIAO_nrf54L15/src/bme280.c @@ -0,0 +1,125 @@ + +/* + Wrapper for Bosch BME280/BMP280 + */ + +#include "bme280.h" + +LOG_MODULE_REGISTER(SolarSensor54l15bme280, LOG_LEVEL_INF); + +SENSOR_DT_READ_IODEV(iodev, DT_COMPAT_GET_ANY_STATUS_OKAY(bosch_bme280), + {SENSOR_CHAN_AMBIENT_TEMP, 0}, + {SENSOR_CHAN_HUMIDITY, 0}, + {SENSOR_CHAN_PRESS, 0}); + +RTIO_DEFINE(ctx, 1, 1); + +static const struct device *const bme280_dev = DEVICE_DT_GET_ANY(bosch_bme280); + +int bme280_init(void) +{ + int err = device_init(bme280_dev); + if (err) { + LOG_ERR("\nDevice %s init failed %d\n", bme280_dev->name, err); + return err; + } + err = pm_device_action_run(bme280_dev, PM_DEVICE_ACTION_SUSPEND); + if (err) { + LOG_ERR("\nDevice %s pm_device_action_run failed %d\n", bme280_dev->name, err); + return err; + } + return 0; +} + +int bme280_check_device(void) +{ + if (bme280_dev == NULL) { + /* No such node, or the node does not have status "okay". */ + LOG_ERR("\nError: no device found.\n"); + return -1; + } + if (!device_is_ready(bme280_dev)) { + LOG_ERR("Error: Device \"%s\" is not ready; " + "check the driver initialization logs for errors.\n", + bme280_dev->name); + return -2; + } + + LOG_INF("Found device \"%s\", getting sensor data\n", bme280_dev->name); + return 0; +} + +int bme280_chipId(void) +{ + if (bme280_dev != NULL && bme280_dev->state->initialized) { + const struct bme280_data *pData = (const struct bme280_data *)bme280_dev->data; + return pData->chip_id; + } + return BMX280_CHIP_ID_NA; +} + +int bme280_read(float *pTemp, float *pHum, float *pPress) +{ + int err; + uint8_t buf[128]; + + if (bme280_dev != NULL) { + err = pm_device_action_run(bme280_dev, PM_DEVICE_ACTION_RESUME); + if (err != 0) { + LOG_ERR("%s: pm_device_action_run() RESUME failed: %d\n", bme280_dev->name, err); + } + err = bme280_check_device(); + + if (err == 0) { + + // bme280_channel_get + err = sensor_read(&iodev, &ctx, buf, 128); + if (err != 0) { + LOG_ERR("%s: sensor_read() failed: %d\n", bme280_dev->name, err); + return err; + } + const struct sensor_decoder_api *decoder; + err = sensor_get_decoder(bme280_dev, &decoder); + + if (err != 0) { + LOG_ERR("%s: sensor_get_decode() failed: %d\n", bme280_dev->name, err); + return err; + } + + if (pTemp != NULL) { + uint32_t temp_fit = 0; + struct sensor_q31_data temp_data = {0}; + if (decoder->decode(buf, (struct sensor_chan_spec) {SENSOR_CHAN_AMBIENT_TEMP, 0}, &temp_fit, 1, &temp_data) > 0) + { + *pTemp = temp_data.readings[0].temperature*1.0f/32768.0f; + LOG_INF("temp: %.2f", (double)*pTemp); + } + } + + if (pPress != NULL) { + uint32_t press_fit = 0; + struct sensor_q31_data press_data = {0}; + if (decoder->decode(buf, (struct sensor_chan_spec) {SENSOR_CHAN_PRESS, 0}, &press_fit, 1, &press_data) > 0) + { + *pPress = press_data.readings[0].pressure*10.0f/256.0f; + LOG_INF("press: %.2f", (double)*pPress); + } + } + + if (pHum != NULL && bme280_chipId() == BME280_CHIP_ID) { + uint32_t hum_fit = 0; + struct sensor_q31_data hum_data = {0}; + if (decoder->decode(buf, (struct sensor_chan_spec) {SENSOR_CHAN_HUMIDITY, 0}, &hum_fit, 1, &hum_data) > 0) + { + *pHum = hum_data.readings[0].humidity*1.0f/1024.0f; + LOG_INF("hum: %.2f", (double)*pHum); + } + } + } + err = pm_device_action_run(bme280_dev, PM_DEVICE_ACTION_SUSPEND); + if (err != 0) { + LOG_ERR("%s: pm_device_action_run() SUSPEND failed: %d\n", bme280_dev->name, err); + } + } + return 0; +} \ No newline at end of file diff --git a/examples/XIAO_nrf54L15/src/bme280.h b/examples/XIAO_nrf54L15/src/bme280.h new file mode 100644 index 0000000..5d1b0c9 --- /dev/null +++ b/examples/XIAO_nrf54L15/src/bme280.h @@ -0,0 +1,105 @@ +#pragma once + +/* + Wrapper for Bosch BME280/BMP280 + */ + +#include +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +#define BMX280_CHIP_ID_NA 0x00 +#define BMP280_CHIP_ID_MP 0x58 +#define BME280_CHIP_ID 0x60 + +struct bme280_decoder_header { + uint64_t timestamp; +} __attribute__((__packed__)); + +struct bme280_reading { + /* Compensated values. */ + int32_t comp_temp; + uint32_t comp_press; + uint32_t comp_humidity; +}; + +struct bme280_encoded_data { + struct bme280_decoder_header header; + struct { + /** Set if `temp` has data */ + uint8_t has_temp: 1; + /** Set if `press` has data */ + uint8_t has_press: 1; + /** Set if `humidity` has data */ + uint8_t has_humidity: 1; + } __attribute__((__packed__)); + struct bme280_reading reading; +}; + +struct bme280_data { + /* Compensation parameters. */ + uint16_t dig_t1; + int16_t dig_t2; + int16_t dig_t3; + uint16_t dig_p1; + int16_t dig_p2; + int16_t dig_p3; + int16_t dig_p4; + int16_t dig_p5; + int16_t dig_p6; + int16_t dig_p7; + int16_t dig_p8; + int16_t dig_p9; + uint8_t dig_h1; + int16_t dig_h2; + uint8_t dig_h3; + int16_t dig_h4; + int16_t dig_h5; + int8_t dig_h6; + + /* Carryover between temperature and pressure/humidity compensation. */ + int32_t t_fine; + + uint8_t chip_id; + + struct bme280_reading reading; +}; + +/** + * @brief Initialize sensor + * + * @retval 0 if initialization was successfull, negative value otherwise + */ +extern int bme280_init(void); +/** + * @brief Check if sensor is ready + * + * @retval 0 if sensor is ready, negative value otherwise + */ +extern int bme280_check_device(void); +/** + * @brief Read values from sensor + * + * @param pTemp pointer to temperature value in °C, may be NULL + * @param pHum pointer to humidity value on %, may be NULL + * @param pPress pointer to pressure in hPa, may be NULL + * + * @retval 0 if sensor could be read, negative value otherwise + */ +extern int bme280_read(float *pTemp, float *pHum, float *pPress); +/** + * @brief Get chip ID + * + * @retval BMX280_CHIP_ID_NA: unknown device, BMP280_CHIP_ID_MP: BMP280, BME280_CHIP_ID: BME280 + */ +extern int bme280_chipId(void); + +#ifdef __cplusplus +} +#endif diff --git a/examples/XIAO_nrf54L15/src/main.cpp b/examples/XIAO_nrf54L15/src/main.cpp new file mode 100644 index 0000000..748314b --- /dev/null +++ b/examples/XIAO_nrf54L15/src/main.cpp @@ -0,0 +1,302 @@ +/* + A ultra low power Home Assistant/BtHome temperature/humidity/pressure sensor device with XIAO nrf54L15 + Average current consumption is as low as 12µA! Can be even more reduced with longer sleep time. + Current during LowPower.deepSleep() would be less, but waking up from deep sleep needs a lot of energy. + So LowPower.sleep() is the better choice for this sensor with TIME_TO_SLEEP=15s. + At 12µA, the sensor should run for more than 3 years on a 350mAh LiPo battery. + */ + +#include + +LOG_MODULE_REGISTER(SolarSensor54l15, LOG_LEVEL_INF); + +#define USE_EXT_ANT 0 +#define USE_BME280 1 +#define USE_ENCRYPTION 1 + +#define TIME_TO_SLEEP 15 +#define TIME_TO_SLEEP_LOW (60*5) + +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include "adc.h" +#include "bme280.h" +#include "wdt.h" +#include "../../src/BtHomeV2Device.h" +#include + +#if !DT_NODE_EXISTS(DT_PATH(zephyr_user)) || \ + !DT_NODE_HAS_PROP(DT_PATH(zephyr_user), io_channels) + #error "No suitable devicetree overlay specified" +#endif + +/****************************************** BTHOME KEY **********************************************/ +#if USE_ENCRYPTION +// 91CDEC4192407AEC3F6FCF04AAB6F7A4 +static const uint8_t bindKey[16] = { + 0x91, 0xCD, 0xEC, 0x41, 0x92, 0x40, 0x7A, 0xEC, + 0x3F, 0x6F, 0xCF, 0x04, 0xAA, 0xB6, 0xF7, 0xA4 +}; +#endif + +/****************************************** WDT **********************************************/ +#define WDT_MAX_WINDOW ((TIME_TO_SLEEP_LOW + 60)*1000) +#define WDT_MIN_WINDOW 0U +#define WDT_OPT WDT_OPT_PAUSE_HALTED_BY_DBG + +/****************************************** DEVICES **********************************************/ +static const struct device *const vbat_reg = DEVICE_DT_GET(DT_NODELABEL(vbat_pwr)); +static const struct device *const rfsw_pwr_reg = DEVICE_DT_GET(DT_NODELABEL(rfsw_pwr)); +#if USE_EXT_ANT +static const struct device *const rfsw_ctl_reg = DEVICE_DT_GET(DT_NODELABEL(rfsw_ctl)); +#endif +static const struct device *const i2c22_dev = DEVICE_DT_GET(DT_NODELABEL(i2c22)); +static const struct device *const i2c30_dev = DEVICE_DT_GET(DT_NODELABEL(i2c30)); +static const struct gpio_dt_spec led = GPIO_DT_SPEC_GET(DT_ALIAS(led0), gpios); + +/****************************************** BLINK_CODE **********************************************/ +void blinkCode(int code) +{ + while(true) { + for (int i = 0; i < code; i++) { + gpio_pin_set_dt(&led, 0); + k_sleep(K_MSEC(100)); + gpio_pin_set_dt(&led, 1); + k_sleep(K_MSEC(300)); + } + k_sleep(K_MSEC(1000)); + } +} + +/****************************************** ADVERTISING **********************************************/ +#define ADV_PARAM BT_LE_ADV_PARAM(BT_LE_ADV_OPT_USE_IDENTITY, \ + 32, \ + 33, NULL) + +/****************************************** BTHome Header **********************************************/ +static struct bt_data ad[] = { + BT_DATA_BYTES(BT_DATA_FLAGS, BT_LE_AD_GENERAL | BT_LE_AD_NO_BREDR), // 3 bytes { len 0x02 type 0x01 data 0x06 } + BT_DATA(BT_DATA_SVC_DATA16, NULL, 0) +}; + +int advertize(BtHomeV2Device *pDev) +{ + uint8_t advertisementData[MAX_ADVERTISEMENT_SIZE]; + uint8_t size = pDev->getAdvertisementData(advertisementData); + // skip first 5 bytes, already in ad struct: + // 1 length=(2) + // 2 BT_DATA_FLAGS + // 3 BT_LE_AD_GENERAL | BT_LE_AD_NO_BREDR + // 4 length=X + // 5 BT_DATA_SVC_DATA16 + ad[1].data_len = size - 5; + ad[1].data = &advertisementData[5]; + + /* Start advertising for 5+95ms */ + int err = bt_le_adv_start(ADV_PARAM, ad, ARRAY_SIZE(ad), NULL, 0); + if (err) { + LOG_ERR("Advertising failed to start (err %d)\n", err); + return 0; + } + /* Flash led for 5ms */ + err = gpio_pin_set_dt(&led, 0); + if (err < 0) { + LOG_ERR("gpio_pin_set_dt failed (err %d)\n", err); + } + k_sleep(K_MSEC(5)); + err = gpio_pin_set_dt(&led, 1); + if (err < 0) { + LOG_ERR("gpio_pin_set_dt failed (err %d)\n", err); + } + k_sleep(K_MSEC(95)); + err = bt_le_adv_stop(); + if (err) { + LOG_ERR("Advertising failed to stop (err %d)\n", err); + return -1; + } + return 0; +} + +/****************************************** MAIN **********************************************/ + +int main(void) +{ + int err; + uint32_t counter = 0; + + LOG_INF("Starting BTHome sensor template\n"); + + // Initialize watchdog + int32_t wdt_channel_id = init_wdt(WDT_MIN_WINDOW, WDT_MAX_WINDOW, WDT_OPT); + if (wdt_channel_id < 0) { + return 0; + } + + err = gpio_pin_configure_dt(&led, GPIO_OUTPUT_ACTIVE); + if (err < 0) { + LOG_ERR("LED GPIO configure failed %d\n", err); + return 0; + } + err = gpio_pin_set_dt(&led, 0); + if (err < 0) { + LOG_ERR("gpio_pin_set_dt failed (err %d)\n", err); + } + // Suspend i2c30: save 145µA while sleeping + err = pm_device_action_run(i2c30_dev, PM_DEVICE_ACTION_SUSPEND); + if (err) { + LOG_ERR("Suspend %s failed %d\n", i2c30_dev->name, err); + } + if (!gpio_is_ready_dt(&led)) { + LOG_ERR("LED GPIO not ready\n"); + return 0; + } + // ADC channel 0 for solar current + err = adcSetup(0); + if (err < 0) { + return 0; + } + // ADC channel 7 for battery voltage + err = adcSetup(7); + if (err < 0) { + return 0; + } + err = device_init(i2c22_dev); + if (err) { + LOG_ERR("\nDevice %s init failed %d\n", i2c22_dev->name, err); + return 0; + } +#if USE_BME280 + int err_bme280 = bme280_init(); + if (err_bme280) { + blinkCode(2); + return err_bme280; + } +#endif + err = pm_device_action_run(i2c22_dev, PM_DEVICE_ACTION_SUSPEND); + if (err) { + LOG_ERR("Suspend %s failed %d\n", i2c22_dev->name, err); + } +#if USE_EXT_ANT + regulator_disable(rfsw_ctl_reg); +#endif + + /* Initialize the Bluetooth Subsystem */ + err = bt_enable(NULL); + if (err) { + LOG_ERR("Bluetooth init failed (err %d)\n", err); + return 0; + } + LOG_INF("Bluetooth initialized\n"); + +#if USE_ENCRYPTION + bt_le_oob oob; + bt_le_oob_get_local(BT_ID_DEFAULT, &oob); + // Leave short and complete name empty, device will be identified by MAC address + BtHomeV2Device dev("", "", false, bindKey, oob.addr.a.val); +#else + BtHomeV2Device dev("", "", true); +#endif + + while(1) { + feed_wdt(wdt_channel_id); + +#if USE_BME280 + err = pm_device_action_run(i2c22_dev, PM_DEVICE_ACTION_RESUME); + if (err != 0) { + LOG_ERR("%s: pm_device_action_run() RESUME failed: %d\n", i2c22_dev->name, err); + } + float temp = 0, hum = 0, press = 0; + err = bme280_read(&temp, &hum, &press); + if (err != 0) { + return err; + } + // Suspend i2c22: save 100µA while sleeping + err = pm_device_action_run(i2c22_dev, PM_DEVICE_ACTION_SUSPEND); + if (err != 0) { + LOG_ERR("%s: pm_device_action_run() SUSPEND failed: %d\n", i2c22_dev->name, err); + } +#endif + int32_t val_mv; + regulator_enable(vbat_reg); + // Wait 5ms for voltage divider to settle + k_sleep(K_MSEC(5)); + // Read battery voltage on channel 7 (pin AIN7/P1.14) + adcRead(&val_mv, NULL, 7); + // Disable battery voltage divider switch supply: save 250µA while sleeping + regulator_disable(vbat_reg); + // Voltage divider divides by 2 + val_mv *= 2; + + int32_t raw; + // Read solar current on channel 0 (differential mode, pins AIN0/P1.04 and AIN1/P1.05) + adcRead(NULL, &raw, 0); + // shunt 10R, 14bits resolution, internal reference (0.9V), gain 2, oversampling 8 + int32_t current_ua = raw*90000/16383; + + counter++; + + // Enable antenna switch supply + regulator_enable(rfsw_pwr_reg); + + // Collect data for advertising packet 1 + dev.resetMeasurement(); + + // Available bytes with encryption: 11, else 23 + // 11 + if (!dev.addCount_0_4294967295(counter)) { + LOG_ERR("addCount_0_4294967295 failed"); + } + // 6 + if (!dev.addVoltage_0_to_65_resolution_0_001(val_mv*0.001f)) { + LOG_ERR("addVoltage_0_to_65_resolution_0_001 failed"); + } + // 3 + if (!dev.addTemperature_neg327_to_327_Resolution_0_01(temp)) { + LOG_ERR("addTemperature_neg327_to_327_Resolution_0_01 failed"); + } + // 0 + // Advertize packet 1 + advertize(&dev); + + // Collect data for advertising packet 2 + dev.resetMeasurement(); + // 11 + if (bme280_chipId() == BME280_CHIP_ID) { + if (!dev.addHumidityPercent_Resolution_0_01(hum)) { + LOG_ERR("addHumidityPercent_Resolution_0_01 failed"); + } + } + // 7 + if (!dev.addCurrentAmps_neg32_to_32_Resolution_0_001(current_ua*0.001f)) { + LOG_ERR("addCurrentAmps_neg32_to_32_Resolution_0_001 failed"); + } + // 4 + if (!dev.addPressureHpa(press)) { + LOG_ERR("addPressureHpa failed"); + } + // 0 + // Advertize packet 2 + advertize(&dev); + + // Disable antenna switch supply: save 67µA while sleeping + regulator_disable(rfsw_pwr_reg); + if (val_mv < 3500) { + k_sleep(K_MSEC(TIME_TO_SLEEP_LOW*1000)); + } else { + k_sleep(K_MSEC(TIME_TO_SLEEP*1000)); + } + } + return 0; +} \ No newline at end of file diff --git a/examples/XIAO_nrf54L15/src/wdt.c b/examples/XIAO_nrf54L15/src/wdt.c new file mode 100644 index 0000000..6f517fc --- /dev/null +++ b/examples/XIAO_nrf54L15/src/wdt.c @@ -0,0 +1,41 @@ + +/* + Wrapper for watchdog timer + */ + +#include "wdt.h" + +LOG_MODULE_REGISTER(SolarSensor54l15wdt, LOG_LEVEL_INF); + +static const struct device *const wdt = DEVICE_DT_GET(DT_ALIAS(watchdog0)); + +int init_wdt(int32_t minWindow, int32_t maxWindow, int32_t options) +{ + if (!device_is_ready(wdt)) { + LOG_ERR("%s: device not ready.\n", wdt->name); + return -1; + } + struct wdt_timeout_cfg wdt_config = { + /* Reset SoC when watchdog timer expires. */ + .flags = WDT_FLAG_RESET_SOC, + /* Expire watchdog after max window */ + .window.min = minWindow, + .window.max = maxWindow, + }; + int wdt_channel_id = wdt_install_timeout(wdt, &wdt_config); + if (wdt_channel_id < 0) { + LOG_ERR("Watchdog install error\n"); + return -2; + } + int err = wdt_setup(wdt, options); + if (err < 0) { + LOG_ERR("Watchdog setup error\n"); + return -3; + } + return wdt_channel_id; +} + +void feed_wdt(int32_t wdt_channel_id) +{ + wdt_feed(wdt, wdt_channel_id); +} \ No newline at end of file diff --git a/examples/XIAO_nrf54L15/src/wdt.h b/examples/XIAO_nrf54L15/src/wdt.h new file mode 100644 index 0000000..d24f546 --- /dev/null +++ b/examples/XIAO_nrf54L15/src/wdt.h @@ -0,0 +1,33 @@ +#pragma once + +/* + Wrapper for watchdog timer + */ + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Initialize watchdog timer + * + * @param minWindow Lower limit of watchdog feed timeout in milliseconds + * @param maxWindow Upper limit of watchdog feed timeout in milliseconds + * @param options configuration options (see WDT_OPT) + * + * @retval channel id if initialization was successfull, negative value otherwise + */ +extern int init_wdt(int32_t minWindow, int32_t maxWindow, int32_t options); +/** + * @brief Feed watchdog timer + * + * @param wdt_channel_id id returned by init_wdt + */ +extern void feed_wdt(int32_t wdt_channel_id); + +#ifdef __cplusplus +} +#endif diff --git a/library.properties b/library.properties index f914d3c..89af08f 100644 --- a/library.properties +++ b/library.properties @@ -1,5 +1,5 @@ name=BTHomeV2-Arduino -version=3.2.0 +version=3.3.0 author=deeja maintainer=deeja sentence=BTHomeV2 advertisement data generator for Arduino. diff --git a/src/BaseDevice.cpp b/src/BaseDevice.cpp index ab6ef68..255f545 100644 --- a/src/BaseDevice.cpp +++ b/src/BaseDevice.cpp @@ -1,6 +1,21 @@ + +#ifdef __ZEPHYR__ +#include +#include +#include +#include +// strnlen not available in ZEPHYR?!? +#define strnlen(s, n) strlen(s) +#else #include "Arduino.h" +#endif + #include "BaseDevice.h" +#ifdef __ZEPHYR__ +LOG_MODULE_REGISTER(BaseDevice, LOG_LEVEL_INF); +#endif + /// @brief /// @param shortName - Short name of the device - sent when space is limited. Max 12 characters. /// @param completeName - Full name of the device - sent when space is available. @@ -27,8 +42,10 @@ BaseDevice::BaseDevice(const char *shortName, const char *completeName, bool isT memcpy(bindKey, key, sizeof(uint8_t) * BIND_KEY_LEN); memcpy(_macAddress, macAddress, BLE_MAC_ADDRESS_LENGTH); +#ifndef __ZEPHYR__ mbedtls_ccm_init(&this->_encryptCTX); mbedtls_ccm_setkey(&this->_encryptCTX, MBEDTLS_CIPHER_ID_AES, bindKey, ENCRYPTION_KEY_LENGTH * 8); +#endif } /// @brief Clear the measurement data. @@ -38,6 +55,17 @@ void BaseDevice::resetMeasurement() _sensorData.clear(); } +/// @brief Return the number of remaining bytes in the sensor data packet for the given size. +/// @details The sensor data packet has a maximum length defined by MEASUREMENT_MAX_LEN. +/// @return Returns the number of remaining bytes. +uint8_t BaseDevice::remainingBytes() +{ + // the index is at the next entry point, so there is one byte extra + static const uint8_t CURRENT_BYTE = 1; + + return (MAX_MEASUREMENT_SIZE - _sensorDataIdx) + CURRENT_BYTE - (_useEncryption ? ENCRYPTION_ADDITIONAL_BYTES : 0); +} + /// @brief Check that there is enough space in the sensor data packet for the given size. /// @details The sensor data packet has a maximum length defined by MEASUREMENT_MAX_LEN. /// @param size @@ -49,11 +77,7 @@ bool BaseDevice::hasEnoughSpace(BtHomeState sensor) bool BaseDevice::hasEnoughSpace(uint8_t size) { - // the index is at the next entry point, so there is one byte extra - static const uint8_t CURRENT_BYTE = 1; - - int remainingBytes = (MAX_MEASUREMENT_SIZE - _sensorDataIdx) + CURRENT_BYTE - (_useEncryption ? ENCRYPTION_ADDITIONAL_BYTES : 0); - return remainingBytes >= size; + return BaseDevice::remainingBytes() >= size; } /// @brief Add a state or step value to the sensor data packet. @@ -104,7 +128,7 @@ bool BaseDevice::addInteger(BtHomeType sensor, T value) { return false; } - auto scaledValue = static_cast(static_cast(value) / sensor.scale); + auto scaledValue = static_cast(static_cast(value) / static_cast(sensor.scale)); return pushBytes(scaledValue, sensor); } @@ -121,7 +145,11 @@ bool BaseDevice::addFloat(BtHomeType sensor, float value) float factor = sensor.scale; float scaledValue = value / factor; - return pushBytes(static_cast(scaledValue), sensor); + if (sensor.signed_value) { + return pushBytes(static_cast(scaledValue), sensor); + } else { + return pushBytes(static_cast(scaledValue), sensor); + } } bool BaseDevice::pushBytes(uint64_t value2, BtHomeState sensor) @@ -131,7 +159,7 @@ bool BaseDevice::pushBytes(uint64_t value2, BtHomeState sensor) for (uint8_t i = 0; i < sensor.byteCount; i++) { - vector.push_back(static_cast((value2 >> (8 * i)) & 0xff)); + vector.push_back(static_cast((value2 >> (8 * i)) & 0xff)); } _sensorData.push_back(vector); @@ -196,8 +224,13 @@ size_t BaseDevice::getAdvertisementData(uint8_t buffer[MAX_ADVERTISEMENT_SIZE]) if (_useEncryption) { +#ifdef __ZEPHYR__ + // encryptionTag will be appended to ciphertext + uint8_t ciphertext[MAX_ADVERTISEMENT_SIZE + MIC_LEN]; +#else uint8_t ciphertext[MAX_ADVERTISEMENT_SIZE]; uint8_t encryptionTag[MIC_LEN]; +#endif uint8_t nonce[NONCE_LEN]; uint8_t *countPtr = (uint8_t *)(&this->_counter); @@ -212,12 +245,16 @@ size_t BaseDevice::getAdvertisementData(uint8_t buffer[MAX_ADVERTISEMENT_SIZE]) nonce[8] = FLAG_VERSION | FLAG_ENCRYPT; memcpy(&nonce[9], countPtr, MIC_LEN); +#ifdef __ZEPHYR__ + // encryptionTag will be appended to ciphertext + bt_ccm_encrypt(bindKey, nonce, sortedBytes, sortedBytesLength, NULL, 0, ciphertext, MIC_LEN); +#else mbedtls_ccm_encrypt_and_tag(&_encryptCTX, sortedBytesLength, nonce, NONCE_LEN, 0, 0, - &sortedBytes[0], &ciphertext[0], encryptionTag, + &sortedBytes[0], &ciphertext[0], encryptionTag, MIC_LEN); - +#endif for (uint8_t i = 0; i < _sensorDataIdx; i++) - { + { serviceData[serviceDataIndex++] = ciphertext[i]; } // writeCounter @@ -225,12 +262,18 @@ size_t BaseDevice::getAdvertisementData(uint8_t buffer[MAX_ADVERTISEMENT_SIZE]) serviceData[serviceDataIndex++] = nonce[10]; serviceData[serviceDataIndex++] = nonce[11]; serviceData[serviceDataIndex++] = nonce[12]; - this->_counter++; + this->_counter++; // writeMIC +#ifdef __ZEPHYR__ + for (uint8_t i = 0; i < 4; i++) { + serviceData[serviceDataIndex++] = ciphertext[_sensorDataIdx + i]; + } +#else serviceData[serviceDataIndex++] = encryptionTag[0]; serviceData[serviceDataIndex++] = encryptionTag[1]; serviceData[serviceDataIndex++] = encryptionTag[2]; serviceData[serviceDataIndex++] = encryptionTag[3]; +#endif } else { @@ -245,7 +288,7 @@ size_t BaseDevice::getAdvertisementData(uint8_t buffer[MAX_ADVERTISEMENT_SIZE]) buffer[bufferDataIndex++] = FLAG1; buffer[bufferDataIndex++] = FLAG2; buffer[bufferDataIndex++] = FLAG3; - byte sd_length = serviceDataIndex; // Generate the length of the Service Data + uint8_t sd_length = serviceDataIndex; // Generate the length of the Service Data buffer[bufferDataIndex++] = sd_length; // Add the length of the Service Data for (size_t i = 0; i < serviceDataIndex; i++) @@ -259,7 +302,8 @@ size_t BaseDevice::getAdvertisementData(uint8_t buffer[MAX_ADVERTISEMENT_SIZE]) // prefer long name size_t completeNameLength = strnlen(_completeName, MAX_LENGTH_COMPLETE_NAME); bool canFitLongName = bufferDataIndex + completeNameLength + TYPE_INDICATOR_SIZE + CURRENT_BYTE <= MAX_ADVERTISEMENT_SIZE; - if (canFitLongName) + // Don't try to append an empty completeName + if (canFitLongName && completeNameLength > 0) { buffer[bufferDataIndex++] = completeNameLength + TYPE_INDICATOR_SIZE; buffer[bufferDataIndex++] = COMPLETE_NAME; @@ -269,7 +313,8 @@ size_t BaseDevice::getAdvertisementData(uint8_t buffer[MAX_ADVERTISEMENT_SIZE]) size_t shortNameLength = strnlen(_shortName, MAX_LENGTH_SHORT_NAME); bool canFitShortName = bufferDataIndex + TYPE_INDICATOR_SIZE + shortNameLength + CURRENT_BYTE <= MAX_ADVERTISEMENT_SIZE; - if (canFitShortName) + // Don't try to append an empty shortName + if (canFitShortName && shortNameLength > 0) { buffer[bufferDataIndex++] = shortNameLength + TYPE_INDICATOR_SIZE; buffer[bufferDataIndex++] = SHORT_NAME; // 0x08 for short name @@ -298,4 +343,4 @@ size_t BaseDevice::getMeasurementByteArray(uint8_t sortedBytes[MAX_ADVERTISEMENT } } return idx; -} +} \ No newline at end of file diff --git a/src/BaseDevice.h b/src/BaseDevice.h index ea2e083..6ae3417 100644 --- a/src/BaseDevice.h +++ b/src/BaseDevice.h @@ -1,7 +1,15 @@ +#ifndef BT_HOME_BASE_DEVICE_H +#define BT_HOME_BASE_DEVICE_H + #include "definitions.h" +#ifndef __ZEPHYR__ #include -#include +#endif +#include "data_types.h" +#ifndef __ZEPHYR__ #include "mbedtls/ccm.h" +#endif + static const size_t MAX_ADVERTISEMENT_SIZE = 31; static const size_t HEADER_SIZE = 9; static const size_t MAX_MEASUREMENT_SIZE = MAX_ADVERTISEMENT_SIZE - HEADER_SIZE; @@ -28,6 +36,7 @@ class BaseDevice bool addSignedInteger(BtHomeType sensor, int64_t value); bool addFloat(BtHomeType sensor, float value); bool addRaw(uint8_t sensor, uint8_t *value, uint8_t size); + uint8_t remainingBytes(); private: bool pushBytes(uint64_t value2, BtHomeState sensor); @@ -42,8 +51,12 @@ class BaseDevice bool _triggerDevice = false; bool _useEncryption = false; uint32_t _counter = 1; +#ifndef __ZEPHYR__ mbedtls_ccm_context _encryptCTX; +#endif uint8_t _macAddress[BLE_MAC_ADDRESS_LENGTH]; uint8_t bindKey[BIND_KEY_LEN]; size_t getMeasurementByteArray(uint8_t sortedBytes[MAX_ADVERTISEMENT_SIZE]); }; + +#endif // BT_HOME_BASE_DEVICE_H \ No newline at end of file diff --git a/src/BtHomeV2Device.cpp b/src/BtHomeV2Device.cpp index 42e10a3..24812d6 100644 --- a/src/BtHomeV2Device.cpp +++ b/src/BtHomeV2Device.cpp @@ -1,8 +1,12 @@ +#ifdef __ZEPHYR__ +#include +#endif + #include "BtHomeV2Device.h" void BtHomeV2Device::clearMeasurementData() { - return _baseDevice.resetMeasurement(); + return BaseDevice::resetMeasurement(); } /// @brief Builds an outgoing wrapper for the current measurement data. @@ -10,452 +14,452 @@ void BtHomeV2Device::clearMeasurementData() /// @return size_t BtHomeV2Device::getAdvertisementData(uint8_t buffer[MAX_ADVERTISEMENT_SIZE]) { - return _baseDevice.getAdvertisementData(buffer); + return BaseDevice::getAdvertisementData(buffer); } -BtHomeV2Device::BtHomeV2Device(const char *shortName, const char *completeName, bool isTriggerDevice) : _baseDevice(shortName, completeName, isTriggerDevice) // Initialize with default device name and trigger-based device flag +BtHomeV2Device::BtHomeV2Device(const char *shortName, const char *completeName, bool isTriggerDevice) : BaseDevice(shortName, completeName, isTriggerDevice) // Initialize with default device name and trigger-based device flag { } -BtHomeV2Device::BtHomeV2Device(const char *shortName, const char *completeName, bool isTriggerBased, uint8_t const* const key, const uint8_t macAddress[BLE_MAC_ADDRESS_LENGTH], uint32_t counter) : _baseDevice(shortName, completeName, isTriggerBased, key, macAddress, counter){ +BtHomeV2Device::BtHomeV2Device(const char *shortName, const char *completeName, bool isTriggerDevice, uint8_t const* const key, const uint8_t macAddress[BLE_MAC_ADDRESS_LENGTH], uint32_t counter) : BaseDevice(shortName, completeName, isTriggerDevice, key, macAddress, counter){ } + bool BtHomeV2Device::addDeviceTypeId(uint16_t deviceTypeId) { - return _baseDevice.addUnsignedInteger(device_type_ID, deviceTypeId); + return BaseDevice::addUnsignedInteger(device_type_ID, deviceTypeId); } bool BtHomeV2Device::addPacketId(uint8_t packetId) { - return _baseDevice.addUnsignedInteger(packet_id, packetId); + return BaseDevice::addUnsignedInteger(packet_id, packetId); } bool BtHomeV2Device::addFirmwareVersion3(uint8_t major, uint8_t minor, uint8_t patch) { uint32_t fwVersion = major << 16 | minor << 8 | patch; - return _baseDevice.addUnsignedInteger(firmware_3_bytes, fwVersion); + return BaseDevice::addUnsignedInteger(firmware_3_bytes, fwVersion); } bool BtHomeV2Device::addFirmwareVersion4(uint8_t major, uint8_t minor, uint8_t patch, uint8_t build) { uint32_t fwVersion = major << 24 | minor << 16 | patch << 8 | build; - return _baseDevice.addUnsignedInteger(firmware_4_bytes, fwVersion); + return BaseDevice::addUnsignedInteger(firmware_4_bytes, fwVersion); } bool BtHomeV2Device::addTemperature_neg44_to_44_Resolution_0_35(float degreesCelsius) { - return _baseDevice.addFloat(temperature_int8_scale_0_35, degreesCelsius); + return BaseDevice::addFloat(temperature_int8_scale_0_35, degreesCelsius); } bool BtHomeV2Device::addTemperature_neg127_to_127_Resolution_1(int8_t degreesCelsius) { - return _baseDevice.addFloat(temperature_int8, degreesCelsius); + return BaseDevice::addFloat(temperature_int8, degreesCelsius); } bool BtHomeV2Device::addTemperature_neg3276_to_3276_Resolution_0_1(float degreesCelsius) { - return _baseDevice.addFloat(temperature_int16_scale_0_1, degreesCelsius); + return BaseDevice::addFloat(temperature_int16_scale_0_1, degreesCelsius); } bool BtHomeV2Device::addTemperature_neg327_to_327_Resolution_0_01(float degreesCelsius) { - return _baseDevice.addFloat(temperature_int16_scale_0_01, degreesCelsius); + return BaseDevice::addFloat(temperature_int16_scale_0_01, degreesCelsius); } bool BtHomeV2Device::addDistanceMetres(float metres) { - return _baseDevice.addFloat(distance_metre, metres); + return BaseDevice::addFloat(distance_metre, metres); } bool BtHomeV2Device::addDistanceMillimetres(uint16_t millimetres) { - return _baseDevice.addUnsignedInteger(distance_millimetre, millimetres); + return BaseDevice::addUnsignedInteger(distance_millimetre, millimetres); } bool BtHomeV2Device::addCount_0_4294967295(uint32_t count) { - return _baseDevice.addUnsignedInteger(count_uint32, count); + return BaseDevice::addUnsignedInteger(count_uint32, count); } bool BtHomeV2Device::addCount_0_255(uint8_t count) { - Serial.print("Adding count 0-255: "); - Serial.println(count); - return _baseDevice.addUnsignedInteger(count_uint8, count); + return BaseDevice::addUnsignedInteger(count_uint8, count); } bool BtHomeV2Device::addCount_0_65535(uint16_t count) { - return _baseDevice.addUnsignedInteger(count_uint16, count); + return BaseDevice::addUnsignedInteger(count_uint16, count); } bool BtHomeV2Device::addCount_neg128_127(int8_t count) { - return _baseDevice.addSignedInteger(count_int8, static_cast(count)); + return BaseDevice::addSignedInteger(count_int8, static_cast(count)); } bool BtHomeV2Device::addCount_neg32768_32767(int16_t count) { - return _baseDevice.addSignedInteger(count_int16, static_cast(count)); + return BaseDevice::addSignedInteger(count_int16, static_cast(count)); } bool BtHomeV2Device::addCount_neg2147483648_2147483647(int32_t count) { - return _baseDevice.addSignedInteger(count_int32, static_cast(count)); + return BaseDevice::addSignedInteger(count_int32, static_cast(count)); } bool BtHomeV2Device::addHumidityPercent_Resolution_0_01(float humidityPercent) { - return _baseDevice.addFloat(humidity_uint16, humidityPercent); + return BaseDevice::addFloat(humidity_uint16, humidityPercent); } bool BtHomeV2Device::addHumidityPercent_Resolution_1(uint8_t humidityPercent) { - return _baseDevice.addFloat(humidity_uint8, humidityPercent); + return BaseDevice::addFloat(humidity_uint8, humidityPercent); } bool BtHomeV2Device::addText(const char text[]) { - return _baseDevice.addRaw(0x53, (uint8_t *)text, strlen(text)); + return BaseDevice::addRaw(0x53, (uint8_t *)text, strlen(text)); } bool BtHomeV2Device::addTime(uint32_t secondsSinceEpoch) { - return _baseDevice.addUnsignedInteger(timestamp, secondsSinceEpoch); + return BaseDevice::addUnsignedInteger(timestamp, secondsSinceEpoch); } bool BtHomeV2Device::addRaw(uint8_t *bytes, uint8_t size) { - return _baseDevice.addRaw(0x54, bytes, size); + return BaseDevice::addRaw(0x54, bytes, size); } bool BtHomeV2Device::addBatteryPercentage(uint8_t batteryPercentage) { - return _baseDevice.addUnsignedInteger(battery_percentage, batteryPercentage); + return BaseDevice::addUnsignedInteger(battery_percentage, batteryPercentage); } bool BtHomeV2Device::setBatteryState(BATTERY_STATE batteryState) { - return _baseDevice.addState(battery_state, batteryState); + return BaseDevice::addState(battery_state, batteryState); } bool BtHomeV2Device::setBatteryChargingState(Battery_Charging_Sensor_Status batteryChargingState) { - return _baseDevice.addState(battery_charging, batteryChargingState); + return BaseDevice::addState(battery_charging, batteryChargingState); } bool BtHomeV2Device::setCarbonMonoxideState(Carbon_Monoxide_Sensor_Status carbonMonoxideState) { - return _baseDevice.addState(carbon_monoxide, carbonMonoxideState); + return BaseDevice::addState(carbon_monoxide, carbonMonoxideState); } bool BtHomeV2Device::setColdState(Cold_Sensor_Status coldState) { - return _baseDevice.addState(cold, coldState); + return BaseDevice::addState(cold, coldState); } bool BtHomeV2Device::setConnectivityState(Connectivity_Sensor_Status connectivityState) { - return _baseDevice.addState(connectivity, connectivityState); + return BaseDevice::addState(connectivity, connectivityState); } bool BtHomeV2Device::setDoorState(Door_Sensor_Status doorState) { - return _baseDevice.addState(door, doorState); + return BaseDevice::addState(door, doorState); } bool BtHomeV2Device::setGarageDoorState(Garage_Door_Sensor_Status garageDoorState) { - return _baseDevice.addState(garage_door, garageDoorState); + return BaseDevice::addState(garage_door, garageDoorState); } bool BtHomeV2Device::setGasState(Gas_Sensor_Status gasState) { - return _baseDevice.addState(gas, gasState); + return BaseDevice::addState(gas, gasState); } bool BtHomeV2Device::setGenericState(Generic_Sensor_Status genericState) { - return _baseDevice.addState(generic_boolean, genericState); + return BaseDevice::addState(generic_boolean, genericState); } bool BtHomeV2Device::setHeatState(Heat_Sensor_Status heatState) { - return _baseDevice.addState(heat, heatState); + return BaseDevice::addState(heat, heatState); } bool BtHomeV2Device::setLightState(Light_Sensor_Status lightState) { - return _baseDevice.addState(light, lightState); + return BaseDevice::addState(light, lightState); } bool BtHomeV2Device::setLockState(Lock_Sensor_Status lockState) { - return _baseDevice.addState(lock, lockState); + return BaseDevice::addState(lock, lockState); } bool BtHomeV2Device::setMoistureState(Moisture_Sensor_Status moistureState) { - return _baseDevice.addState(moisture, moistureState); + return BaseDevice::addState(moisture, moistureState); } bool BtHomeV2Device::setMotionState(Motion_Sensor_Status motionState) { - return _baseDevice.addState(motion, motionState); + return BaseDevice::addState(motion, motionState); } bool BtHomeV2Device::setMovingState(Moving_Sensor_Status movingState) { - return _baseDevice.addState(moving, movingState); + return BaseDevice::addState(moving, movingState); } bool BtHomeV2Device::setOccupancyState(Occupancy_Sensor_Status occupancyState) { - return _baseDevice.addState(occupancy, occupancyState); + return BaseDevice::addState(occupancy, occupancyState); } bool BtHomeV2Device::setOpeningState(Opening_Sensor_Status openingState) { - return _baseDevice.addState(opening, openingState); + return BaseDevice::addState(opening, openingState); } bool BtHomeV2Device::setPlugState(Plug_Sensor_Status plugState) { - return _baseDevice.addState(plug, plugState); + return BaseDevice::addState(plug, plugState); } bool BtHomeV2Device::setPowerState(Power_Sensor_Status powerState) { - return _baseDevice.addState(power, powerState); + return BaseDevice::addState(power, powerState); } bool BtHomeV2Device::setPresenceState(Presence_Sensor_Status presenceState) { - return _baseDevice.addState(presence, presenceState); + return BaseDevice::addState(presence, presenceState); } bool BtHomeV2Device::setProblemState(Problem_Sensor_Status problemState) { - return _baseDevice.addState(problem, problemState); + return BaseDevice::addState(problem, problemState); } bool BtHomeV2Device::setRunningState(Running_Sensor_Status runningState) { - return _baseDevice.addState(running, runningState); + return BaseDevice::addState(running, runningState); } bool BtHomeV2Device::setSafetyState(Safety_Sensor_Status safetyState) { - return _baseDevice.addState(safety, safetyState); + return BaseDevice::addState(safety, safetyState); } bool BtHomeV2Device::setSmokeState(Smoke_Sensor_Status smokeState) { - return _baseDevice.addState(smoke, smokeState); + return BaseDevice::addState(smoke, smokeState); } bool BtHomeV2Device::setSoundState(Sound_Sensor_Status soundState) { - return _baseDevice.addState(sound, soundState); + return BaseDevice::addState(sound, soundState); } bool BtHomeV2Device::setTamperState(Tamper_Sensor_Status tamperState) { - return _baseDevice.addState(tamper, tamperState); + return BaseDevice::addState(tamper, tamperState); } bool BtHomeV2Device::setVibrationState(Vibration_Sensor_Status vibrationState) { - return _baseDevice.addState(vibration, vibrationState); + return BaseDevice::addState(vibration, vibrationState); } bool BtHomeV2Device::setWindowState(Window_Sensor_Status windowState) { - return _baseDevice.addState(window, windowState); + return BaseDevice::addState(window, windowState); } bool BtHomeV2Device::setButtonEvent(Button_Event_Status buttonEvent) { - return _baseDevice.addState(button, buttonEvent); + return BaseDevice::addState(button, buttonEvent); } bool BtHomeV2Device::setDimmerEvent(Dimmer_Event_Status dimmerEvent, uint8_t steps) { - return _baseDevice.addState(dimmer, dimmerEvent, steps); + return BaseDevice::addState(dimmer, dimmerEvent, steps); } bool BtHomeV2Device::addAccelerationMs2(float value) { - return _baseDevice.addFloat(acceleration, value); + return BaseDevice::addFloat(acceleration, value); } bool BtHomeV2Device::addChannel(uint8_t value) { - return _baseDevice.addUnsignedInteger(channel, value); + return BaseDevice::addUnsignedInteger(channel, value); } bool BtHomeV2Device::addCo2Ppm(uint16_t value) { - return _baseDevice.addUnsignedInteger(co2, value); + return BaseDevice::addUnsignedInteger(co2, value); } bool BtHomeV2Device::addConductivityMicrosecondsPerCm(float value) { - return _baseDevice.addFloat(conductivity, value); + return BaseDevice::addFloat(conductivity, value); } bool BtHomeV2Device::addCurrentAmps_neg32_to_32_Resolution_0_001(float value) { - return _baseDevice.addFloat(current_int16, value); + return BaseDevice::addFloat(current_int16, value); } bool BtHomeV2Device::addCurrentAmps_0_65_Resolution_0_001(float value) { - return _baseDevice.addFloat(current_uint16, value); + return BaseDevice::addFloat(current_uint16, value); } bool BtHomeV2Device::addDewPointDegreesCelsius(float value) { - return _baseDevice.addFloat(dewpoint, value); + return BaseDevice::addFloat(dewpoint, value); } bool BtHomeV2Device::addDirectionDegrees(float value) { - return _baseDevice.addFloat(direction, value); + return BaseDevice::addFloat(direction, value); } bool BtHomeV2Device::addDurationSeconds(float value) { - return _baseDevice.addFloat(duration_uint24, value); + return BaseDevice::addFloat(duration_uint24, value); } bool BtHomeV2Device::addEnergyKwh_0_to_16777(float value) { - return _baseDevice.addFloat(energy_uint24, value); + return BaseDevice::addFloat(energy_uint24, value); } bool BtHomeV2Device::addEnergyKwh_0_to_4294967(float value) { - return _baseDevice.addFloat(energy_uint32, value); + return BaseDevice::addFloat(energy_uint32, value); } bool BtHomeV2Device::addGasM3_0_to_16777(float value) { - return _baseDevice.addFloat(gas_uint24, value); + return BaseDevice::addFloat(gas_uint24, value); } bool BtHomeV2Device::addGasM3_0_to_4294967(float value) { - return _baseDevice.addFloat(gas_uint32, value); + return BaseDevice::addFloat(gas_uint32, value); } bool BtHomeV2Device::addGyroscopeDegreeSeconds(float value) { - return _baseDevice.addFloat(gyroscope, value); + return BaseDevice::addFloat(gyroscope, value); } bool BtHomeV2Device::addIlluminanceLux(float value) { - return _baseDevice.addFloat(illuminance, value); + return BaseDevice::addFloat(illuminance, value); } bool BtHomeV2Device::addMassKg(float value) { - return _baseDevice.addFloat(mass_kg, value); + return BaseDevice::addFloat(mass_kg, value); } bool BtHomeV2Device::addMassLb(float value) { - return _baseDevice.addFloat(mass_lb, value); + return BaseDevice::addFloat(mass_lb, value); } bool BtHomeV2Device::addMoisturePercent_Resolution_1(uint8_t value) { - return _baseDevice.addUnsignedInteger(moisture_uint8, value); + return BaseDevice::addUnsignedInteger(moisture_uint8, value); } bool BtHomeV2Device::addMoisturePercent_Resolution_0_01(float value) { - return _baseDevice.addFloat(moisture_uint16, value); + return BaseDevice::addFloat(moisture_uint16, value); } bool BtHomeV2Device::addPm2_5UgM3(uint16_t value) { - return _baseDevice.addUnsignedInteger(pm2_5, value); + return BaseDevice::addUnsignedInteger(pm2_5, value); } bool BtHomeV2Device::addPm10UgM3(uint16_t value) { - return _baseDevice.addUnsignedInteger(pm10, value); + return BaseDevice::addUnsignedInteger(pm10, value); } bool BtHomeV2Device::addPower_neg21474836_to_21474836_resolution_0_01(float value) { - return _baseDevice.addFloat(power_int32, value); + return BaseDevice::addFloat(power_int32, value); } bool BtHomeV2Device::addPower_0_to_167772_resolution_0_01(float value) { - return _baseDevice.addFloat(power_uint24, value); + return BaseDevice::addFloat(power_uint24, value); } bool BtHomeV2Device::addPrecipitationMm(float value) { - return _baseDevice.addFloat(precipitation, value); + return BaseDevice::addFloat(precipitation, value); } bool BtHomeV2Device::addPressureHpa(float value) { - return _baseDevice.addFloat(pressure, value); + return BaseDevice::addFloat(pressure, value); } bool BtHomeV2Device::addRotationDegrees(float value) { - return _baseDevice.addFloat(rotation, value); + return BaseDevice::addFloat(rotation, value); } bool BtHomeV2Device::addSpeedMs(float value) { - return _baseDevice.addFloat(speed, value); + return BaseDevice::addFloat(speed, value); } bool BtHomeV2Device::addTvocUgm3(uint16_t value) { - return _baseDevice.addUnsignedInteger(tvoc, value); + return BaseDevice::addUnsignedInteger(tvoc, value); } bool BtHomeV2Device::addVoltage_0_to_6550_resolution_0_1(float value) { - return _baseDevice.addFloat(voltage_0_1, value); + return BaseDevice::addFloat(voltage_0_1, value); } bool BtHomeV2Device::addVoltage_0_to_65_resolution_0_001(float value) { - return _baseDevice.addFloat(voltage_0_001, value); + return BaseDevice::addFloat(voltage_0_001, value); } bool BtHomeV2Device::addVolumeLitres_0_to_6555_resolution_0_1(float value) { - return _baseDevice.addFloat(volume_uint16_scale_0_1, value); + return BaseDevice::addFloat(volume_uint16_scale_0_1, value); } bool BtHomeV2Device::addVolumeLitres_0_to_65550_resolution_1(uint16_t value) { - return _baseDevice.addUnsignedInteger(volume_uint16_scale_1, value); + return BaseDevice::addUnsignedInteger(volume_uint16_scale_1, value); } bool BtHomeV2Device::addVolumeLitres_0_to_4294967_resolution_0_001(float value) { - return _baseDevice.addFloat(volume_uint32, value); + return BaseDevice::addFloat(volume_uint32, value); } bool BtHomeV2Device::addVolumeStorageLitres(float value) { - return _baseDevice.addFloat(volume_storage, value); + return BaseDevice::addFloat(volume_storage, value); } bool BtHomeV2Device::addVolumeFlowRateM3hr(float value) { - return _baseDevice.addFloat(volume_flow_rate, value); + return BaseDevice::addFloat(volume_flow_rate, value); } bool BtHomeV2Device::addUvIndex(float value) { - return _baseDevice.addFloat(UV_index, value); + return BaseDevice::addFloat(UV_index, value); } bool BtHomeV2Device::addWaterLitres(float value) { - return _baseDevice.addFloat(water_litre, value); + return BaseDevice::addFloat(water_litre, value); } + diff --git a/src/BtHomeV2Device.h b/src/BtHomeV2Device.h index 80be747..72a47bb 100644 --- a/src/BtHomeV2Device.h +++ b/src/BtHomeV2Device.h @@ -3,7 +3,9 @@ // https://bthome.io/format/ +#ifndef __ZEPHYR__ #include +#endif #include "BaseDevice.h" /** @@ -18,7 +20,7 @@ enum BATTERY_STATE BATTERY_STATE_LOW = 1 }; -class BtHomeV2Device +class BtHomeV2Device : public BaseDevice { public: /// @brief @@ -199,8 +201,9 @@ class BtHomeV2Device bool addWaterLitres(float value); -private: - BaseDevice _baseDevice; +// Don't use GNU style inheritance, use C++ standard instead +// private: +// BaseDevice _baseDevice; }; -#endif // BT_HOME_H +#endif // BT_HOME_H \ No newline at end of file diff --git a/src/data_types.h b/src/data_types.h index 5efd078..7101901 100644 --- a/src/data_types.h +++ b/src/data_types.h @@ -2,20 +2,41 @@ #define BT_HOME_DATA_TYPES_H #pragma once + +#ifdef __ZEPHYR__ +#include +#include +#else #include +#endif + #include // You can use struct inheritance in C++ to inherit properties. // For example, BtHomeType can inherit from BtHomeState if you want to reuse the 'id' field: +#ifdef __ZEPHYR__ +class BtHomeState +#else struct BtHomeState +#endif { +#ifdef __ZEPHYR__ +public: +#endif uint8_t id; uint8_t byteCount; }; +#ifdef __ZEPHYR__ +class BtHomeType : public BtHomeState +#else struct BtHomeType : public BtHomeState +#endif { +#ifdef __ZEPHYR__ +public: +#endif float scale; // Multiplier to apply before serializing bool signed_value; // true if value is signed, false if unsigned @@ -318,4 +339,4 @@ enum Window_Sensor_Status Window_Sensor_Status_Open = 1 }; -#endif // BT_HOME_DATA_TYPES_H +#endif // BT_HOME_DATA_TYPES_H \ No newline at end of file