Bosch BSEC integration completed

This commit is contained in:
Klaus K Wilting 2018-11-25 16:05:30 +01:00
parent 165f2813f5
commit b85dc829a5
15 changed files with 183 additions and 202 deletions

View File

@ -47,7 +47,7 @@ Depending on board hardware following features are supported:
- Silicon unique ID - Silicon unique ID
- Battery voltage monitoring - Battery voltage monitoring
- GPS (Generic serial NMEA, or Quectel L76 I2C) - GPS (Generic serial NMEA, or Quectel L76 I2C)
- MEMS sensor (Bosch BME680) - Environmental sensor (Bosch BME680 I2C)
Target platform must be selected in [platformio.ini](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/platformio.ini).<br> Target platform must be selected in [platformio.ini](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/platformio.ini).<br>
Hardware dependent settings (pinout etc.) are stored in board files in /hal directory. If you want to use a ESP32 board which is not yet supported, use hal file generic.h and tailor pin mappings to your needs. Pull requests for new boards welcome.<br> Hardware dependent settings (pinout etc.) are stored in board files in /hal directory. If you want to use a ESP32 board which is not yet supported, use hal file generic.h and tailor pin mappings to your needs. Pull requests for new boards welcome.<br>
@ -198,12 +198,20 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
byte 1: Beacon RSSI reception level byte 1: Beacon RSSI reception level
byte 2: Beacon identifier (0..255) byte 2: Beacon identifier (0..255)
**Port #7:** BME680 query result **Port #7:** Environmental sensor query result
bytes 1-2: Temperature [°C] bytes 1-2: Temperature [°C]
bytes 3-4: Pressure [hPa] bytes 3-4: Pressure [hPa]
bytes 5-6: Humidity [%] bytes 5-6: Humidity [%]
bytes 7-8: Gas resistance [kOhm] bytes 7-8: Indoor air quality index (0..500), see below
Indoor air quality classification:
0-50 good
51-100 average
101-150 little bad
151-200 bad
201-300 worse
301-500 very bad
# Remote control # Remote control

View File

@ -3,30 +3,27 @@
#include "globals.h" #include "globals.h"
#include <Wire.h> #include <Wire.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include "bsec_integration.h" #include "bsec_integration.h"
#include "bsec_integration.c"
extern bmeStatus_t extern bmeStatus_t
bme_status; // Make struct for storing gps data globally available bme_status; // Make struct for storing gps data globally available
extern TaskHandle_t BmeTask;
int bme_init(); int bme_init();
bool bme_read(); void bme_loop(void *pvParameters);
void user_delay_ms(uint32_t period); int8_t i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
int64_t get_timestamp_us(); uint16_t len);
int8_t i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
int8_t user_i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len);
uint16_t len); void output_ready(int64_t timestamp, float iaq, uint8_t iaq_accuracy,
int8_t user_i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, float temperature, float humidity, float pressure,
uint16_t len); float raw_temperature, float raw_humidity, float gas,
bsec_library_return_t bsec_status, float static_iaq,
float co2_equivalent, float breath_voc_equivalent);
uint32_t state_load(uint8_t *state_buffer, uint32_t n_buffer); uint32_t state_load(uint8_t *state_buffer, uint32_t n_buffer);
void state_save(const uint8_t *state_buffer, uint32_t length); void state_save(const uint8_t *state_buffer, uint32_t length);
uint32_t config_load(uint8_t *config_buffer, uint32_t n_buffer); uint32_t config_load(uint8_t *config_buffer, uint32_t n_buffer);
void user_delay_ms(uint32_t period);
int64_t get_timestamp_us();
#endif #endif

View File

@ -67,10 +67,14 @@ typedef struct {
} gpsStatus_t; } gpsStatus_t;
typedef struct { typedef struct {
float temperature; // Temperature in degrees Centigrade float iaq; // IAQ signal
uint16_t pressure; // Barometic pressure in hecto pascals uint8_t iaq_accuracy; // accuracy of IAQ signal
float humidity; // Relative humidity in percent float temperature; // temperature signal
uint16_t gas_resistance; // Resistance in MOhms float humidity; // humidity signal
float pressure; // pressure signal
float raw_temperature; // raw temperature signal
float raw_humidity; // raw humidity signal
float gas; // raw gas sensor signal
} bmeStatus_t; } bmeStatus_t;
// global variables // global variables

View File

@ -13,6 +13,7 @@ extern gpsStatus_t
gps_status; // Make struct for storing gps data globally available gps_status; // Make struct for storing gps data globally available
extern TaskHandle_t GpsTask; extern TaskHandle_t GpsTask;
int gps_init(void);
void gps_read(void); void gps_read(void);
void gps_loop(void *pvParameters); void gps_loop(void *pvParameters);

View File

@ -69,8 +69,8 @@ fill in the various parameters as shown below
gas_sensor.dev_id = BME680_I2C_ADDR_PRIMARY; gas_sensor.dev_id = BME680_I2C_ADDR_PRIMARY;
gas_sensor.intf = BME680_I2C_INTF; gas_sensor.intf = BME680_I2C_INTF;
gas_sensor.read = user_i2c_read; gas_sensor.read = i2c_read;
gas_sensor.write = user_i2c_write; gas_sensor.write = i2c_write;
gas_sensor.delay_ms = user_delay_ms; gas_sensor.delay_ms = user_delay_ms;
/* amb_temp can be set to 25 prior to configuring the gas sensor /* amb_temp can be set to 25 prior to configuring the gas sensor
* or by performing a few temperature readings without operating the gas sensor. * or by performing a few temperature readings without operating the gas sensor.
@ -225,7 +225,7 @@ int8_t user_spi_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint1
return rslt; return rslt;
} }
int8_t user_i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len) int8_t i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len)
{ {
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */ int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */
@ -252,7 +252,7 @@ int8_t user_i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16
return rslt; return rslt;
} }
int8_t user_i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len) int8_t i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len)
{ {
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */ int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */

View File

@ -9,12 +9,12 @@
;env_default = generic ;env_default = generic
;env_default = ebox ;env_default = ebox
;env_default = eboxtube ;env_default = eboxtube
env_default = heltec ;env_default = heltec
;env_default = heltecv2 ;env_default = heltecv2
;env_default = ttgov1 ;env_default = ttgov1
;env_default = ttgov2 ;env_default = ttgov2
;env_default = ttgov21old ;env_default = ttgov21old
;env_default = ttgov21new env_default = ttgov21new
;env_default = ttgobeam ;env_default = ttgobeam
;env_default = lopy ;env_default = lopy
;env_default = lopy4 ;env_default = lopy4
@ -29,7 +29,7 @@ description = Paxcounter is a proof-of-concept ESP32 device for metering passeng
[common] [common]
; for release_version use max. 10 chars total, use any decimal format like "a.b.c" ; for release_version use max. 10 chars total, use any decimal format like "a.b.c"
release_version = 1.6.83 release_version = 1.6.84
; DEBUG LEVEL: For production run set to 0, otherwise device will leak RAM while running! ; DEBUG LEVEL: For production run set to 0, otherwise device will leak RAM while running!
; 0=None, 1=Error, 2=Warn, 3=Info, 4=Debug, 5=Verbose ; 0=None, 1=Error, 2=Warn, 3=Info, 4=Debug, 5=Verbose
debug_level = 0 debug_level = 0
@ -60,10 +60,9 @@ lib_deps_all =
${common.lib_deps_rgbled} ${common.lib_deps_rgbled}
${common.lib_deps_gps} ${common.lib_deps_gps}
build_flags_basic = build_flags_basic =
'-include $PROJECTSRC_DIR/hal/${PIOENV}.h' -include $PROJECTSRC_DIR\\hal\\${PIOENV}.h
'-include $PROJECTSRC_DIR/paxcounter.conf' -include $PROJECTSRC_DIR\\paxcounter.conf
-w -w
;'-DARDUINO_LMIC_PROJECT_CONFIG_H="/$PROJECTSRC_DIR/lmic_config.h"'
'-DARDUINO_LMIC_PROJECT_CONFIG_H=../../../src/lmic_config.h' '-DARDUINO_LMIC_PROJECT_CONFIG_H=../../../src/lmic_config.h'
'-DCORE_DEBUG_LEVEL=${common.debug_level}' '-DCORE_DEBUG_LEVEL=${common.debug_level}'
'-DLOG_LOCAL_LEVEL=${common.debug_level}' '-DLOG_LOCAL_LEVEL=${common.debug_level}'

View File

@ -5,47 +5,43 @@
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = "main";
#define NUM_USED_OUTPUTS 8
bmeStatus_t bme_status; bmeStatus_t bme_status;
TaskHandle_t BmeTask;
// initialize BME680 sensor // initialize BME680 sensor
int bme_init(void) { int bme_init(void) {
return_values_init ret = {BME680_OK, BSEC_OK}; // struct bme680_dev gas_sensor;
struct bme680_dev gas_sensor;
Wire.begin(HAS_BME, 400000); // I2C connect to BME680 sensor with 400 KHz Wire.begin(HAS_BME, 400000); // I2C connect to BME680 sensor with 400 KHz
/* Call to the function which initializes the BSEC library // Call to the function which initializes the BSEC library
* Switch on low-power mode and provide no temperature offset */ // Switch on low-power mode and provide no temperature offset
ret = bsec_iot_init(BSEC_SAMPLE_RATE_LP, 0.0f, user_i2c_write, user_i2c_read,
user_delay_ms, state_load, config_load); return_values_init ret =
if (ret.bme680_status) { bsec_iot_init(BSEC_SAMPLE_RATE_LP, 0.0f, i2c_write, i2c_read,
/* Could not intialize BME680 */ user_delay_ms, state_load, config_load);
return (int)ret.bme680_status;
} else if (ret.bsec_status) { if ((int)ret.bme680_status) {
/* Could not intialize BSEC library */ ESP_LOGE(TAG, "Could not initialize BME680, error %d", (int)ret.bme680_status);
return (int)ret.bsec_status; } else if ((int)ret.bsec_status) {
ESP_LOGE(TAG, "Could not initialize BSEC library, error %d", (int)ret.bsec_status);
} else {
ESP_LOGI(TAG, "BME680 sensor found and initialized");
return 1;
} }
return 0;
} }
bool bme_read(void) { void output_ready(int64_t timestamp, float iaq, uint8_t iaq_accuracy,
/* float temperature, float humidity, float pressure,
float raw_temperature, float raw_humidity, float gas,
bsec_library_return_t bsec_status, float static_iaq,
float co2_equivalent, float breath_voc_equivalent) {
bool ret = bme.performReading(); bme_status.temperature = temperature;
if (ret) { bme_status.humidity = humidity;
// read current BME data and buffer in global struct bme_status.pressure = pressure;
bme_status.temperature = bme.temperature; bme_status.iaq = iaq;
bme_status.pressure = (uint16_t)(bme.pressure / 100.0); // convert Pa ->
hPa bme_status.humidity = bme.humidity; bme_status.gas_resistance =
(uint16_t)(bme.gas_resistance / 1000.0); // convert Ohm -> kOhm
ESP_LOGI(TAG, "BME680 sensor data read success");
} else {
ESP_LOGI(TAG, "BME680 sensor read error");
}
return ret;
*/
} }
// loop function which reads and processes data based on sensor settings // loop function which reads and processes data based on sensor settings
@ -54,19 +50,16 @@ void bme_loop(void *pvParameters) {
configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check
#ifdef HAS_BME #ifdef HAS_BME
// State is saved every 10.000 samples, which means every 10.000 * 3 secs = // State is saved every 10.000 samples, which means every 10.000 * 3 secs =
// 500 minutes // 500 minutes
bsec_iot_loop(sleep, get_timestamp_us, output_ready, state_save, 10000); bsec_iot_loop(user_delay_ms, get_timestamp_us, output_ready, state_save,
10000);
vTaskDelete(NULL); // shoud never be reached
#endif #endif
vTaskDelete(BmeTask); // should never be reached
} // bme_loop() } // bme_loop()
int8_t user_i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, int8_t i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
uint16_t len) { uint16_t len) {
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */ int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */
uint16_t i; uint16_t i;
@ -82,8 +75,8 @@ int8_t user_i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
return rslt; return rslt;
} }
int8_t user_i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, int8_t i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
uint16_t len) { uint16_t len) {
int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */ int8_t rslt = 0; /* Return 0 for Success, non-zero for failure */
uint16_t i; uint16_t i;
@ -153,35 +146,6 @@ uint32_t config_load(uint8_t *config_buffer, uint32_t n_buffer) {
* @return none * @return none
*/ */
void ulp_plus_button_press() {
/* We call bsec_update_subscription() in order to instruct BSEC to perform an
* extra measurement at the next possible time slot
*/
bsec_sensor_configuration_t requested_virtual_sensors[1];
uint8_t n_requested_virtual_sensors = 1;
bsec_sensor_configuration_t
required_sensor_settings[BSEC_MAX_PHYSICAL_SENSOR];
uint8_t n_required_sensor_settings = BSEC_MAX_PHYSICAL_SENSOR;
bsec_library_return_t status = BSEC_OK;
/* To trigger a ULP plus, we request the IAQ virtual sensor with a specific
* sample rate code */
requested_virtual_sensors[0].sensor_id = BSEC_OUTPUT_IAQ;
requested_virtual_sensors[0].sample_rate =
BSEC_SAMPLE_RATE_ULP_MEASUREMENT_ON_DEMAND;
/* Call bsec_update_subscription() to enable/disable the requested virtual
* sensors */
status = bsec_update_subscription(
requested_virtual_sensors, n_requested_virtual_sensors,
required_sensor_settings, &n_required_sensor_settings);
/* The status code would tell is if the request was accepted. It will be
* rejected if the sensor is not already in ULP mode, or if the time
* difference between requests is too short, for example. */
}
void user_delay_ms(uint32_t period) { vTaskDelay(period / portTICK_PERIOD_MS); } void user_delay_ms(uint32_t period) { vTaskDelay(period / portTICK_PERIOD_MS); }
int64_t get_timestamp_us() { return (int64_t)millis() * 1000; } int64_t get_timestamp_us() { return (int64_t)millis() * 1000; }

View File

@ -32,11 +32,6 @@ void doHousekeeping() {
} }
#endif #endif
#ifdef HAS_BME
// read BME280 sensor if present
bme_read();
#endif
// task storage debugging // // task storage debugging //
ESP_LOGD(TAG, "Wifiloop %d bytes left", ESP_LOGD(TAG, "Wifiloop %d bytes left",
uxTaskGetStackHighWaterMark(wifiSwitchTask)); uxTaskGetStackHighWaterMark(wifiSwitchTask));
@ -45,6 +40,9 @@ void doHousekeeping() {
#ifdef HAS_GPS #ifdef HAS_GPS
ESP_LOGD(TAG, "Gpsloop %d bytes left", uxTaskGetStackHighWaterMark(GpsTask)); ESP_LOGD(TAG, "Gpsloop %d bytes left", uxTaskGetStackHighWaterMark(GpsTask));
#endif #endif
#ifdef HAS_BME
ESP_LOGD(TAG, "Bmeloop %d bytes left", uxTaskGetStackHighWaterMark(BmeTask));
#endif
#if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED) #if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED)
ESP_LOGD(TAG, "LEDloop %d bytes left", ESP_LOGD(TAG, "LEDloop %d bytes left",

View File

@ -9,6 +9,38 @@ TinyGPSPlus gps;
gpsStatus_t gps_status; gpsStatus_t gps_status;
TaskHandle_t GpsTask; TaskHandle_t GpsTask;
#ifdef GPS_SERIAL
HardwareSerial GPS_Serial(1);
#endif
// initialize and configure GPS
int gps_init(void) {
int ret = 1;
#if defined GPS_SERIAL
GPS_Serial.begin(GPS_SERIAL);
ESP_LOGI(TAG, "Using serial GPS");
#elif defined GPS_I2C
Wire.begin(GPS_I2C, 400000); // I2C connect to GPS device with 400 KHz
Wire.beginTransmission(GPS_ADDR);
Wire.write(0x00); // dummy write
ret = Wire.endTransmission(); // check if chip is seen on i2c bus
if (ret) {
ESP_LOGE(TAG,
"Quectel L76 GPS chip not found on i2c bus, bus error %d. "
"Stopping GPS-Task.",
ret);
ret = 0;
} else {
ESP_LOGI(TAG, "Quectel L76 GPS chip found");
}
#endif
return ret;
} // gps_init()
// read GPS data and cast to global struct // read GPS data and cast to global struct
void gps_read() { void gps_read() {
gps_status.latitude = (int32_t)(gps.location.lat() * 1e6); gps_status.latitude = (int32_t)(gps.location.lat() * 1e6);
@ -26,30 +58,6 @@ void gps_loop(void *pvParameters) {
configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check
// initialize and, if needed, configure, GPS
#if defined GPS_SERIAL
HardwareSerial GPS_Serial(1);
GPS_Serial.begin(GPS_SERIAL);
#elif defined GPS_I2C
uint8_t ret;
Wire.begin(GPS_I2C, 400000); // I2C connect to GPS device with 400 KHz
Wire.beginTransmission(GPS_ADDR);
Wire.write(0x00); // dummy write
ret = Wire.endTransmission(); // check if chip is seen on i2c bus
if (ret) {
ESP_LOGE(TAG,
"Quectel L76 GPS chip not found on i2c bus, bus error %d. "
"Stopping GPS-Task.",
ret);
vTaskDelete(GpsTask);
} else {
ESP_LOGI(TAG, "Quectel L76 GPS chip found.");
}
#endif
while (1) { while (1) {
if (cfg.payloadmask && GPS_DATA) { if (cfg.payloadmask && GPS_DATA) {

View File

@ -13,16 +13,12 @@
#define SPI_SCLK GPIO_NUM_18 #define SPI_SCLK GPIO_NUM_18
#define SPI_CS GPIO_NUM_5 #define SPI_CS GPIO_NUM_5
////////////// test //////////
// enable only if device has these sensors, otherwise comment these lines // enable only if device has these sensors, otherwise comment these lines
// BME680 sensor on I2C bus // BME680 sensor on I2C bus
#define HAS_BME GPIO_NUM_21, GPIO_NUM_22 // SDA, SCL #define HAS_BME GPIO_NUM_21, GPIO_NUM_22 // SDA, SCL
// #define BME_ADDR BME680_I2C_ADDR_PRIMARY // i2c addr 0x76
#define BME_ADDR BME680_I2C_ADDR_SECONDARY // i2c addr 0x77
//
// user defined sensors // user defined sensors
//#define HAS_SENSORS 1 // comment out if device has user defined sensors //#define HAS_SENSORS 1 // comment out if device has user defined sensors
////////////// test //////////
#define CFG_sx1276_radio 1 // select LoRa chip #define CFG_sx1276_radio 1 // select LoRa chip
//#define CFG_sx1272_radio 1 // select LoRa chip //#define CFG_sx1272_radio 1 // select LoRa chip

View File

@ -10,7 +10,12 @@
// disable brownout detection (avoid unexpected reset on some boards) // disable brownout detection (avoid unexpected reset on some boards)
#define DISABLE_BROWNOUT 1 // comment out if you want to keep brownout feature #define DISABLE_BROWNOUT 1 // comment out if you want to keep brownout feature
#define HAS_BME 0x76 // BME680 sensor on I2C bus; comment out if not present // enable only if device has these sensors, otherwise comment these lines
// BME680 sensor on I2C bus
#define HAS_BME GPIO_NUM_21, GPIO_NUM_22 // SDA, SCL
// user defined sensors
//#define HAS_SENSORS 1 // comment out if device has user defined sensors
#define HAS_LED 13 // ESP32 GPIO12 (pin22) On Board LED #define HAS_LED 13 // ESP32 GPIO12 (pin22) On Board LED
#define LED_ACTIVE_LOW 1 // Onboard LED is active when pin is LOW #define LED_ACTIVE_LOW 1 // Onboard LED is active when pin is LOW

View File

@ -5,16 +5,12 @@
// Hardware related definitions for TTGO T-Beam board // Hardware related definitions for TTGO T-Beam board
////////////// test //////////
// enable only if device has these sensors, otherwise comment these lines // enable only if device has these sensors, otherwise comment these lines
// BME680 sensor on I2C bus // BME680 sensor on I2C bus
#define HAS_BME GPIO_NUM_21, GPIO_NUM_22 // SDA, SCL #define HAS_BME GPIO_NUM_21, GPIO_NUM_22 // SDA, SCL
// #define BME_ADDR BME680_I2C_ADDR_PRIMARY // i2c addr 0x76
#define BME_ADDR BME680_I2C_ADDR_SECONDARY // i2c addr 0x77
//
// user defined sensors // user defined sensors
//#define HAS_SENSORS 1 // comment out if device has user defined sensors //#define HAS_SENSORS 1 // comment out if device has user defined sensors
////////////// test //////////
#define HAS_LORA 1 // comment out if device shall not send data via LoRa #define HAS_LORA 1 // comment out if device shall not send data via LoRa
#define CFG_sx1276_radio 1 // HPD13A LoRa SoC #define CFG_sx1276_radio 1 // HPD13A LoRa SoC

View File

@ -8,8 +8,6 @@
// This settings are for boards labeled v1.6 on pcb, NOT for v1.5 or older // This settings are for boards labeled v1.6 on pcb, NOT for v1.5 or older
*/ */
#define HAS_BME 0x77 // BME680 sensor on I2C bus (SDI=21/SCL=22); comment out if not present
#define HAS_LORA 1 // comment out if device shall not send data via LoRa #define HAS_LORA 1 // comment out if device shall not send data via LoRa
#define CFG_sx1276_radio 1 // HPD13A LoRa SoC #define CFG_sx1276_radio 1 // HPD13A LoRa SoC

View File

@ -34,7 +34,8 @@ IDLE 0 0 ESP32 arduino scheduler -> runs wifi sniffer
looptask 1 1 arduino core -> runs the LMIC LoRa stack looptask 1 1 arduino core -> runs the LMIC LoRa stack
irqhandler 1 1 executes tasks triggered by irq irqhandler 1 1 executes tasks triggered by irq
gpsloop 1 2 reads data from GPS over serial or i2c gpsloop 1 2 reads data from GPS via serial or i2c
bmeloop 1 2 reads data from BME sensor via i2c
IDLE 1 0 ESP32 arduino scheduler IDLE 1 0 ESP32 arduino scheduler
ESP32 hardware timers ESP32 hardware timers
@ -90,6 +91,29 @@ void setup() {
esp_log_set_vprintf(redirect_log); esp_log_set_vprintf(redirect_log);
#endif #endif
ESP_LOGI(TAG, "Starting %s v%s", PRODUCTNAME, PROGVERSION);
// print chip information on startup if in verbose mode
#ifdef VERBOSE
esp_chip_info_t chip_info;
esp_chip_info(&chip_info);
ESP_LOGI(TAG,
"This is ESP32 chip with %d CPU cores, WiFi%s%s, silicon revision "
"%d, %dMB %s Flash",
chip_info.cores, (chip_info.features & CHIP_FEATURE_BT) ? "/BT" : "",
(chip_info.features & CHIP_FEATURE_BLE) ? "/BLE" : "",
chip_info.revision, spi_flash_get_chip_size() / (1024 * 1024),
(chip_info.features & CHIP_FEATURE_EMB_FLASH) ? "embedded"
: "external");
ESP_LOGI(TAG, "ESP32 SDK: %s", ESP.getSdkVersion());
ESP_LOGI(TAG, "Free RAM: %d bytes", ESP.getFreeHeap());
#ifdef HAS_GPS
ESP_LOGI(TAG, "TinyGPS+ v%s", TinyGPSPlus::libraryVersion());
#endif
#endif // verbose
// read (and initialize on first run) runtime settings from NVRAM // read (and initialize on first run) runtime settings from NVRAM
loadConfig(); // includes initialize if necessary loadConfig(); // includes initialize if necessary
@ -100,12 +124,21 @@ void setup() {
// switch on power LED if we have 2 LEDs, else use it for status // switch on power LED if we have 2 LEDs, else use it for status
#ifdef HAS_RGB_LED #ifdef HAS_RGB_LED
switch_LED(LED_ON); switch_LED(LED_ON);
strcat_P(features, " RGB");
rgb_set_color(COLOR_PINK);
#endif #endif
#endif #endif
#ifdef HAS_RGB_LED #if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED)
rgb_set_color(COLOR_PINK); // start led loop
strcat_P(features, " RGB"); ESP_LOGI(TAG, "Starting LEDloop...");
xTaskCreatePinnedToCore(ledLoop, // task function
"ledloop", // name of task
1024, // stack size of task
(void *)1, // parameter of the task
3, // priority of the task
&ledLoopTask, // task handle
0); // CPU core
#endif #endif
// initialize wifi antenna // initialize wifi antenna
@ -156,12 +189,31 @@ void setup() {
// initialize gps // initialize gps
#ifdef HAS_GPS #ifdef HAS_GPS
strcat_P(features, " GPS"); strcat_P(features, " GPS");
if (gps_init()) {
ESP_LOGI(TAG, "Starting GPSloop...");
xTaskCreatePinnedToCore(gps_loop, // task function
"gpsloop", // name of task
2048, // stack size of task
(void *)1, // parameter of the task
2, // priority of the task
&GpsTask, // task handle
1); // CPU core
}
#endif #endif
// initialize bme // initialize bme
#ifdef HAS_BME #ifdef HAS_BME
strcat_P(features, " BME"); strcat_P(features, " BME");
bme_init(); if (bme_init()) {
ESP_LOGI(TAG, "Starting BMEloop...");
xTaskCreatePinnedToCore(bme_loop, // task function
"bmeloop", // name of task
4096, // stack size of task
(void *)1, // parameter of the task
2, // priority of the task
&BmeTask, // task handle
1); // CPU core
}
#endif #endif
// initialize sensors // initialize sensors
@ -186,29 +238,6 @@ void setup() {
strcat_P(features, " OUIFLT"); strcat_P(features, " OUIFLT");
#endif #endif
ESP_LOGI(TAG, "Starting %s v%s", PRODUCTNAME, PROGVERSION);
// print chip information on startup if in verbose mode
#ifdef VERBOSE
esp_chip_info_t chip_info;
esp_chip_info(&chip_info);
ESP_LOGI(TAG,
"This is ESP32 chip with %d CPU cores, WiFi%s%s, silicon revision "
"%d, %dMB %s Flash",
chip_info.cores, (chip_info.features & CHIP_FEATURE_BT) ? "/BT" : "",
(chip_info.features & CHIP_FEATURE_BLE) ? "/BLE" : "",
chip_info.revision, spi_flash_get_chip_size() / (1024 * 1024),
(chip_info.features & CHIP_FEATURE_EMB_FLASH) ? "embedded"
: "external");
ESP_LOGI(TAG, "ESP32 SDK: %s", ESP.getSdkVersion());
ESP_LOGI(TAG, "Free RAM: %d bytes", ESP.getFreeHeap());
#ifdef HAS_GPS
ESP_LOGI(TAG, "TinyGPS+ v%s", TinyGPSPlus::libraryVersion());
#endif
#endif // verbose
// initialize display // initialize display
#ifdef HAS_DISPLAY #ifdef HAS_DISPLAY
strcat_P(features, " OLED"); strcat_P(features, " OLED");
@ -277,17 +306,6 @@ void setup() {
// function gets it's seed from RF noise // function gets it's seed from RF noise
get_salt(); // get new 16bit for salting hashes get_salt(); // get new 16bit for salting hashes
#ifdef HAS_GPS
ESP_LOGI(TAG, "Starting GPSloop...");
xTaskCreatePinnedToCore(gps_loop, // task function
"gpsloop", // name of task
2048, // stack size of task
(void *)1, // parameter of the task
2, // priority of the task
&GpsTask, // task handle
1); // CPU core
#endif
// start state machine // start state machine
ESP_LOGI(TAG, "Starting IRQ Handler..."); ESP_LOGI(TAG, "Starting IRQ Handler...");
xTaskCreatePinnedToCore(irqHandler, // task function xTaskCreatePinnedToCore(irqHandler, // task function
@ -298,18 +316,6 @@ void setup() {
&irqHandlerTask, // task handle &irqHandlerTask, // task handle
1); // CPU core 1); // CPU core
#if (HAS_LED != NOT_A_PIN) || defined(HAS_RGB_LED)
// start led loop
ESP_LOGI(TAG, "Starting LEDloop...");
xTaskCreatePinnedToCore(ledLoop, // task function
"ledloop", // name of task
1024, // stack size of task
(void *)1, // parameter of the task
3, // priority of the task
&ledLoopTask, // task handle
0); // CPU core
#endif
// start wifi channel rotation task // start wifi channel rotation task
ESP_LOGI(TAG, "Starting Wifi Channel rotation..."); ESP_LOGI(TAG, "Starting Wifi Channel rotation...");
xTaskCreatePinnedToCore(switchWifiChannel, // task function xTaskCreatePinnedToCore(switchWifiChannel, // task function

View File

@ -104,14 +104,15 @@ void PayloadConvert::addBME(bmeStatus_t value) {
#ifdef HAS_BME #ifdef HAS_BME
int16_t temperature = (int16_t)(value.temperature); // float -> int int16_t temperature = (int16_t)(value.temperature); // float -> int
uint16_t humidity = (uint16_t)(value.humidity); // float -> int uint16_t humidity = (uint16_t)(value.humidity); // float -> int
uint16_t iaq = (uint16_t)(value.iaq); // float -> int
buffer[cursor++] = highByte(temperature); buffer[cursor++] = highByte(temperature);
buffer[cursor++] = lowByte(temperature); buffer[cursor++] = lowByte(temperature);
buffer[cursor++] = highByte(value.pressure); buffer[cursor++] = highByte(value.pressure);
buffer[cursor++] = lowByte(value.pressure); buffer[cursor++] = lowByte(value.pressure);
buffer[cursor++] = highByte(humidity); buffer[cursor++] = highByte(humidity);
buffer[cursor++] = lowByte(humidity); buffer[cursor++] = lowByte(humidity);
buffer[cursor++] = highByte(value.gas_resistance); buffer[cursor++] = highByte(value.iaq);
buffer[cursor++] = lowByte(value.gas_resistance); buffer[cursor++] = lowByte(value.iaq);
#endif #endif
} }
@ -194,7 +195,7 @@ void PayloadConvert::addBME(bmeStatus_t value) {
writeTemperature(value.temperature); writeTemperature(value.temperature);
writeUint16(value.pressure); writeUint16(value.pressure);
writeHumidity(value.humidity); writeHumidity(value.humidity);
writeUint16(value.gas_resistance); writeUint16(value.iaq);
#endif #endif
} }
@ -373,8 +374,8 @@ void PayloadConvert::addBME(bmeStatus_t value) {
uint16_t pressure = value.pressure * 10; uint16_t pressure = value.pressure * 10;
// 0.5% per bit => 0 .. 128 %C // 0.5% per bit => 0 .. 128 %C
uint8_t humidity = (uint8_t)(value.humidity * 2.0); uint8_t humidity = (uint8_t)(value.humidity * 2.0);
// 0.01 Ohm per bit => 0 .. 655,36 Ohm // 0.01 IAQ per bit => 0 .. 655,36 IAQ
uint16_t gas = value.gas_resistance * 100; uint16_t iaq = (uint16_t) value.iaq * 100;
#if (PAYLOAD_ENCODER == 3) #if (PAYLOAD_ENCODER == 3)
buffer[cursor++] = LPP_TEMPERATURE_CHANNEL; buffer[cursor++] = LPP_TEMPERATURE_CHANNEL;
@ -397,8 +398,8 @@ void PayloadConvert::addBME(bmeStatus_t value) {
buffer[cursor++] = LPP_GAS_CHANNEL; buffer[cursor++] = LPP_GAS_CHANNEL;
#endif #endif
buffer[cursor++] = LPP_ANALOG_INPUT; // 2 bytes 0.01 Signed buffer[cursor++] = LPP_ANALOG_INPUT; // 2 bytes 0.01 Signed
buffer[cursor++] = highByte(gas); buffer[cursor++] = highByte(iaq);
buffer[cursor++] = lowByte(gas); buffer[cursor++] = lowByte(iaq);
#endif // HAS_BME #endif // HAS_BME
} }