diff --git a/README.md b/README.md
index 88a52486..51f9c25a 100644
--- a/README.md
+++ b/README.md
@@ -47,7 +47,7 @@ Depending on board hardware following features are supported:
- Silicon unique ID
- Battery voltage monitoring
- 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).
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.
@@ -151,7 +151,6 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
byte 1-2: Number of unique pax, first seen on Wifi
byte 3-4: Number of unique pax, first seen on Bluetooth [0 if BT disabled]
- bytes 5-18: GPS data, format see Port #4 (appended only, if GPS is present and has a fix)
**Port #2:** Device status query result
@@ -177,12 +176,12 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
byte 13: Wifi antenna switch (0=internal, 1=external) [default 0]
byte 14: Vendorfilter mode (0=disabled, 1=enabled) [default 0]
byte 15: RGB LED luminosity (0..100 %) [default 30]
- byte 16: GPS send data mode (1=on, 0=ff) [default 1]
+ byte 16: Payload filter mask
byte 17: Beacon proximity alarm mode (1=on, 0=off) [default 0]
bytes 18-28: Software version (ASCII format, terminating with zero)
-**Port #4:** GPS query result
+**Port #4:** GPS query result (device answers only if has GPS and GPS has a fix)
bytes 1-4: Latitude
bytes 5-8: Longitude
@@ -199,12 +198,20 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
byte 1: Beacon RSSI reception level
byte 2: Beacon identifier (0..255)
-**Port #7:** BME680 query result
+**Port #7:** Environmental sensor query result
bytes 1-2: Temperature [°C]
bytes 3-4: Pressure [hPa]
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
@@ -306,6 +313,11 @@ Note: all settings are stored in NVRAM and will be reloaded when device starts.
byte 1 = beacon ID (0..255)
bytes 2..7 = beacon MAC with 6 digits (e.g. MAC 80:ab:00:01:02:03 -> 0x80ab00010203)
+0x13 set user sensor mode
+
+ byte 1 = user sensor number (1..4)
+ byte 2 = sensor mode (0 = disabled / 1 = enabled [default])
+
0x80 get device configuration
Device answers with it's current configuration on Port 3.
diff --git a/include/bme680mems.h b/include/bme680mems.h
new file mode 100644
index 00000000..4828a063
--- /dev/null
+++ b/include/bme680mems.h
@@ -0,0 +1,29 @@
+#ifndef _BME680MEMS_H
+#define _BME680MEMS_H
+
+#include "globals.h"
+#include
+#include "bsec_integration.h"
+
+extern bmeStatus_t
+ bme_status; // Make struct for storing gps data globally available
+extern TaskHandle_t BmeTask;
+
+int bme_init();
+void bme_loop(void *pvParameters);
+int8_t i2c_read(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);
+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);
+uint32_t state_load(uint8_t *state_buffer, uint32_t n_buffer);
+void state_save(const uint8_t *state_buffer, uint32_t length);
+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
\ No newline at end of file
diff --git a/include/bme680read.h b/include/bme680read.h
deleted file mode 100644
index 4573f22f..00000000
--- a/include/bme680read.h
+++ /dev/null
@@ -1,15 +0,0 @@
-#ifndef _HAS_BME
-#define _HAS_BME
-
-#include "globals.h"
-#include
-#include
-#include "Adafruit_BME680.h"
-
-extern bmeStatus_t
- bme_status; // Make struct for storing gps data globally available
-
-void bme_init();
-bool bme_read();
-
-#endif
\ No newline at end of file
diff --git a/include/globals.h b/include/globals.h
index 575bc931..528291c9 100644
--- a/include/globals.h
+++ b/include/globals.h
@@ -9,6 +9,26 @@
#include
#include
+// bits in payloadmask for filtering payload data
+#define GPS_DATA (0x01)
+#define ALARM_DATA (0x02)
+#define MEMS_DATA (0x04)
+#define COUNT_DATA (0x08)
+#define SENSOR1_DATA (0x10)
+#define SENSOR2_DATA (0x20)
+#define SENSOR3_DATA (0x40)
+#define SENSOR4_DATA (0x80)
+
+// bits in configmask for device runmode control
+#define GPS_MODE (0x01)
+#define ALARM_MODE (0x02)
+#define BEACON_MODE (0x04)
+#define UPDATE_MODE (0x08)
+#define FILTER_MODE (0x10)
+#define ANTENNA_MODE (0x20)
+#define BLE_MODE (0x40)
+#define SCREEN_MODE (0x80)
+
// Struct holding devices's runtime configuration
typedef struct {
uint8_t lorasf; // 7-12, lora spreadfactor
@@ -25,9 +45,9 @@ typedef struct {
uint8_t wifiant; // 0=internal, 1=external (for LoPy/LoPy4)
uint8_t vendorfilter; // 0=disabled, 1=enabled
uint8_t rgblum; // RGB Led luminosity (0..100%)
- uint8_t gpsmode; // 0=disabled, 1=enabled
uint8_t monitormode; // 0=disabled, 1=enabled
uint8_t runmode; // 0=normal, 1=update
+ uint8_t payloadmask; // bitswitches for payload data
char version[10]; // Firmware version
} configData_t;
@@ -47,10 +67,14 @@ typedef struct {
} gpsStatus_t;
typedef struct {
- float temperature; // Temperature in degrees Centigrade
- uint16_t pressure; // Barometic pressure in hecto pascals
- float humidity; // Relative humidity in percent
- uint16_t gas_resistance; // Resistance in MOhms
+float iaq; // IAQ signal
+uint8_t iaq_accuracy; // accuracy of IAQ signal
+float temperature; // temperature signal
+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;
// global variables
@@ -75,7 +99,7 @@ extern TaskHandle_t irqHandlerTask, wifiSwitchTask;
#endif
#ifdef HAS_BME
-#include "bme680read.h"
+#include "bme680mems.h"
#endif
#ifdef HAS_LORA
@@ -102,4 +126,8 @@ extern TaskHandle_t irqHandlerTask, wifiSwitchTask;
#include "antenna.h"
#endif
+#ifdef HAS_SENSORS
+#include "sensor.h"
+#endif
+
#endif
\ No newline at end of file
diff --git a/include/gpsread.h b/include/gpsread.h
index 484aa9fb..7f432c47 100644
--- a/include/gpsread.h
+++ b/include/gpsread.h
@@ -13,6 +13,7 @@ extern gpsStatus_t
gps_status; // Make struct for storing gps data globally available
extern TaskHandle_t GpsTask;
+int gps_init(void);
void gps_read(void);
void gps_loop(void *pvParameters);
diff --git a/include/lorawan.h b/include/lorawan.h
index 3e930c7e..a0ea4880 100644
--- a/include/lorawan.h
+++ b/include/lorawan.h
@@ -3,6 +3,7 @@
#include "globals.h"
#include "rcommand.h"
+#include
// LMIC-Arduino LoRaWAN Stack
#include
diff --git a/include/ota.h b/include/ota.h
index 54230762..3c6c8318 100644
--- a/include/ota.h
+++ b/include/ota.h
@@ -5,7 +5,8 @@
#include "globals.h"
#include "battery.h"
-#include "update.h"
+//#include "update.h"
+#include
#include
#include
#include
diff --git a/include/payload.h b/include/payload.h
index 5acd0a76..91bf3778 100644
--- a/include/payload.h
+++ b/include/payload.h
@@ -47,6 +47,7 @@ public:
void addGPS(gpsStatus_t value);
void addBME(bmeStatus_t value);
void addButton(uint8_t value);
+ void addSensor(uint8_t[]);
#if PAYLOAD_ENCODER == 1 // format plain
diff --git a/include/sensor.h b/include/sensor.h
new file mode 100644
index 00000000..6e6b837b
--- /dev/null
+++ b/include/sensor.h
@@ -0,0 +1,8 @@
+#ifndef _SENSOR_H
+#define _SENSOR_H
+
+uint8_t sensor_mask(uint8_t sensor_no);
+uint8_t * sensor_read(uint8_t sensor);
+void sensor_init(void);
+
+#endif
\ No newline at end of file
diff --git a/include/update.h b/include/update.h
deleted file mode 100644
index 87c6f35c..00000000
--- a/include/update.h
+++ /dev/null
@@ -1,184 +0,0 @@
-#ifndef ESP8266UPDATER_H
-#define ESP8266UPDATER_H
-
-#include
-#include
-#include
-#include "esp_partition.h"
-
-#define UPDATE_ERROR_OK (0)
-#define UPDATE_ERROR_WRITE (1)
-#define UPDATE_ERROR_ERASE (2)
-#define UPDATE_ERROR_READ (3)
-#define UPDATE_ERROR_SPACE (4)
-#define UPDATE_ERROR_SIZE (5)
-#define UPDATE_ERROR_STREAM (6)
-#define UPDATE_ERROR_MD5 (7)
-#define UPDATE_ERROR_MAGIC_BYTE (8)
-#define UPDATE_ERROR_ACTIVATE (9)
-#define UPDATE_ERROR_NO_PARTITION (10)
-#define UPDATE_ERROR_BAD_ARGUMENT (11)
-#define UPDATE_ERROR_ABORT (12)
-
-#define UPDATE_SIZE_UNKNOWN 0xFFFFFFFF
-
-#define U_FLASH 0
-#define U_SPIFFS 100
-#define U_AUTH 200
-
-class UpdateClass {
- public:
- typedef std::function THandlerFunction_Progress;
-
- UpdateClass();
-
- /*
- This callback will be called when Update is receiving data
- */
- UpdateClass& onProgress(THandlerFunction_Progress fn);
-
- /*
- Call this to check the space needed for the update
- Will return false if there is not enough space
- */
- bool begin(size_t size=UPDATE_SIZE_UNKNOWN, int command = U_FLASH, int ledPin = -1, uint8_t ledOn = LOW);
-
- /*
- Writes a buffer to the flash and increments the address
- Returns the amount written
- */
- size_t write(uint8_t *data, size_t len);
-
- /*
- Writes the remaining bytes from the Stream to the flash
- Uses readBytes() and sets UPDATE_ERROR_STREAM on timeout
- Returns the bytes written
- Should be equal to the remaining bytes when called
- Usable for slow streams like Serial
- */
- size_t writeStream(Stream &data);
-
- /*
- If all bytes are written
- this call will write the config to eboot
- and return true
- If there is already an update running but is not finished and !evenIfRemainanig
- or there is an error
- this will clear everything and return false
- the last error is available through getError()
- evenIfRemaining is helpfull when you update without knowing the final size first
- */
- bool end(bool evenIfRemaining = false);
-
- /*
- Aborts the running update
- */
- void abort();
-
- /*
- Prints the last error to an output stream
- */
- void printError(Stream &out);
-
- /*
- sets the expected MD5 for the firmware (hexString)
- */
- bool setMD5(const char * expected_md5);
-
- /*
- returns the MD5 String of the sucessfully ended firmware
- */
- String md5String(void){ return _md5.toString(); }
-
- /*
- populated the result with the md5 bytes of the sucessfully ended firmware
- */
- void md5(uint8_t * result){ return _md5.getBytes(result); }
-
- //Helpers
- uint8_t getError(){ return _error; }
- void clearError(){ _error = UPDATE_ERROR_OK; }
- bool hasError(){ return _error != UPDATE_ERROR_OK; }
- bool isRunning(){ return _size > 0; }
- bool isFinished(){ return _progress == _size; }
- size_t size(){ return _size; }
- size_t progress(){ return _progress; }
- size_t remaining(){ return _size - _progress; }
-
- /*
- Template to write from objects that expose
- available() and read(uint8_t*, size_t) methods
- faster than the writeStream method
- writes only what is available
- */
- template
- size_t write(T &data){
- size_t written = 0;
- if (hasError() || !isRunning())
- return 0;
-
- size_t available = data.available();
- while(available) {
- if(_bufferLen + available > remaining()){
- available = remaining() - _bufferLen;
- }
- if(_bufferLen + available > 4096) {
- size_t toBuff = 4096 - _bufferLen;
- data.read(_buffer + _bufferLen, toBuff);
- _bufferLen += toBuff;
- if(!_writeBuffer())
- return written;
- written += toBuff;
- } else {
- data.read(_buffer + _bufferLen, available);
- _bufferLen += available;
- written += available;
- if(_bufferLen == remaining()) {
- if(!_writeBuffer()) {
- return written;
- }
- }
- }
- if(remaining() == 0)
- return written;
- available = data.available();
- }
- return written;
- }
-
- /*
- check if there is a firmware on the other OTA partition that you can bootinto
- */
- bool canRollBack();
- /*
- set the other OTA partition as bootable (reboot to enable)
- */
- bool rollBack();
-
- private:
- void _reset();
- void _abort(uint8_t err);
- bool _writeBuffer();
- bool _verifyHeader(uint8_t data);
- bool _verifyEnd();
-
-
- uint8_t _error;
- uint8_t *_buffer;
- size_t _bufferLen;
- size_t _size;
- THandlerFunction_Progress _progress_callback;
- uint32_t _progress;
- uint32_t _command;
- const esp_partition_t* _partition;
-
- String _target_md5;
- MD5Builder _md5;
-
- int _ledPin;
- uint8_t _ledOn;
-};
-
-extern UpdateClass Update;
-
-#endif
\ No newline at end of file
diff --git a/include/wifiscan.h b/include/wifiscan.h
index 9ad06422..d5e2f456 100644
--- a/include/wifiscan.h
+++ b/include/wifiscan.h
@@ -10,21 +10,6 @@
#define MAC_SNIFF_WIFI 0
#define MAC_SNIFF_BLE 1
-typedef struct {
- unsigned frame_ctrl : 16;
- unsigned duration_id : 16;
- uint8_t addr1[6]; /* receiver address */
- uint8_t addr2[6]; /* sender address */
- uint8_t addr3[6]; /* filtering address */
- unsigned sequence_ctrl : 16;
- uint8_t addr4[6]; /* optional */
-} wifi_ieee80211_mac_hdr_t;
-
-typedef struct {
- wifi_ieee80211_mac_hdr_t hdr;
- uint8_t payload[0]; /* network data ended with 4 bytes csum (CRC32) */
-} wifi_ieee80211_packet_t;
-
void wifi_sniffer_init(void);
void IRAM_ATTR wifi_sniffer_packet_handler(void *buff, wifi_promiscuous_pkt_type_t type);
void switchWifiChannel(void * parameter);
diff --git a/lib/Bosch-BSEC/LICENSE b/lib/Bosch-BSEC/LICENSE
new file mode 100644
index 00000000..ab7a8c8b
--- /dev/null
+++ b/lib/Bosch-BSEC/LICENSE
@@ -0,0 +1,39 @@
+Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+Redistributions of source code must retain the above copyright
+notice, this list of conditions and the following disclaimer.
+
+Redistributions in binary form must reproduce the above copyright
+notice, this list of conditions and the following disclaimer in the
+documentation and/or other materials provided with the distribution.
+
+Neither the name of the copyright holder nor the names of the
+contributors may be used to endorse or promote products derived from
+this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
+IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
+OR CONTRIBUTORS BE LIABLE FOR ANY
+DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
+OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
+PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
+
+The information provided is believed to be accurate and reliable.
+The copyright holder assumes no responsibility
+for the consequences of use
+of such information nor for any infringement of patents or
+other rights of third parties which may result from its use.
+No license is granted by implication or otherwise under any patent or
+patent rights of the copyright holder.
\ No newline at end of file
diff --git a/lib/Bosch-BSEC/README.md b/lib/Bosch-BSEC/README.md
new file mode 100644
index 00000000..0a7e0ee4
--- /dev/null
+++ b/lib/Bosch-BSEC/README.md
@@ -0,0 +1,282 @@
+# BME680 sensor API
+
+## Introduction
+
+This package contains the Bosch Sensortec's BME680 gas sensor API
+
+The sensor driver package includes bme680.h, bme680.c and bme680_defs.h files
+
+## Version
+
+File | Version | Date
+--------------|---------|-------------
+bme680.c | 3.5.9 | 19 Jun 2018
+bme680.h | 3.5.9 | 19 Jun 2018
+bme680_defs.h | 3.5.9 | 19 Jun 2018
+
+## Integration details
+
+* Integrate bme680.h, bme680_defs.h and bme680.c file in to your project.
+* Include the bme680.h file in your code like below.
+
+``` c
+#include "bme680.h"
+```
+
+## File information
+
+* bme680_defs.h : This header file has the constants, macros and datatype declarations.
+* bme680.h : This header file contains the declarations of the sensor driver APIs.
+* bme680.c : This source file contains the definitions of the sensor driver APIs.
+
+## Supported sensor interfaces
+
+* SPI 4-wire
+* I2C
+
+## Usage guide
+
+### Initializing the sensor
+
+To initialize the sensor, you will first need to create a device structure. You
+can do this by creating an instance of the structure bme680_dev. Then go on to
+fill in the various parameters as shown below
+
+#### Example for SPI 4-Wire
+
+``` c
+ struct bme680_dev gas_sensor;
+
+ /* You may assign a chip select identifier to be handled later */
+ gas_sensor.dev_id = 0;
+ gas_sensor.intf = BME680_SPI_INTF;
+ gas_sensor.read = user_spi_read;
+ gas_sensor.write = user_spi_write;
+ gas_sensor.delay_ms = user_delay_ms;
+ /* 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.
+ */
+ gas_sensor.amb_temp = 25;
+
+ int8_t rslt = BME680_OK;
+ rslt = bme680_init(&gas_sensor);
+```
+
+#### Example for I2C
+
+``` c
+ struct bme680_dev gas_sensor;
+
+ gas_sensor.dev_id = BME680_I2C_ADDR_PRIMARY;
+ gas_sensor.intf = BME680_I2C_INTF;
+ gas_sensor.read = i2c_read;
+ gas_sensor.write = i2c_write;
+ gas_sensor.delay_ms = user_delay_ms;
+ /* 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.
+ */
+ gas_sensor.amb_temp = 25;
+
+
+ int8_t rslt = BME680_OK;
+ rslt = bme680_init(&gas_sensor);
+```
+
+Regarding compensation functions for temperature, pressure, humidity and gas we have two implementations.
+
+ - Integer version
+ - floating point version
+
+By default, Integer version is used in the API
+
+If the user needs the floating point version, the user has to un-comment BME680_FLOAT_POINT_COMPENSATION macro
+in bme680_defs.h file or to add it in the compiler flags.
+
+### Configuring the sensor
+
+#### Example for configuring the sensor in forced mode
+
+``` c
+ uint8_t set_required_settings;
+
+ /* Set the temperature, pressure and humidity settings */
+ gas_sensor.tph_sett.os_hum = BME680_OS_2X;
+ gas_sensor.tph_sett.os_pres = BME680_OS_4X;
+ gas_sensor.tph_sett.os_temp = BME680_OS_8X;
+ gas_sensor.tph_sett.filter = BME680_FILTER_SIZE_3;
+
+ /* Set the remaining gas sensor settings and link the heating profile */
+ gas_sensor.gas_sett.run_gas = BME680_ENABLE_GAS_MEAS;
+ /* Create a ramp heat waveform in 3 steps */
+ gas_sensor.gas_sett.heatr_temp = 320; /* degree Celsius */
+ gas_sensor.gas_sett.heatr_dur = 150; /* milliseconds */
+
+ /* Select the power mode */
+ /* Must be set before writing the sensor configuration */
+ gas_sensor.power_mode = BME680_FORCED_MODE;
+
+ /* Set the required sensor settings needed */
+ set_required_settings = BME680_OST_SEL | BME680_OSP_SEL | BME680_OSH_SEL | BME680_FILTER_SEL
+ | BME680_GAS_SENSOR_SEL;
+
+ /* Set the desired sensor configuration */
+ rslt = bme680_set_sensor_settings(set_required_settings,&gas_sensor);
+
+ /* Set the power mode */
+ rslt = bme680_set_sensor_mode(&gas_sensor);
+
+
+```
+
+### Reading sensor data
+
+#### Example for reading all sensor data
+
+``` c
+ /* Get the total measurement duration so as to sleep or wait till the
+ * measurement is complete */
+ uint16_t meas_period;
+ bme680_get_profile_dur(&meas_period, &gas_sensor);
+
+ struct bme680_field_data data;
+
+ while(1)
+ {
+ user_delay_ms(meas_period); /* Delay till the measurement is ready */
+
+ rslt = bme680_get_sensor_data(&data, &gas_sensor);
+
+ printf("T: %.2f degC, P: %.2f hPa, H %.2f %%rH ", data.temperature / 100.0f,
+ data.pressure / 100.0f, data.humidity / 1000.0f );
+ /* Avoid using measurements from an unstable heating setup */
+ if(data.status & BME680_GASM_VALID_MSK)
+ printf(", G: %d ohms", data.gas_resistance);
+
+ printf("\r\n");
+
+ /* Trigger the next measurement if you would like to read data out continuously */
+ if (gas_sensor.power_mode == BME680_FORCED_MODE) {
+ rslt = bme680_set_sensor_mode(&gas_sensor);
+ }
+ }
+```
+
+### Templates for function pointers
+
+``` c
+
+void user_delay_ms(uint32_t period)
+{
+ /*
+ * Return control or wait,
+ * for a period amount of milliseconds
+ */
+}
+
+int8_t user_spi_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 */
+
+ /*
+ * The parameter dev_id can be used as a variable to select which Chip Select pin has
+ * to be set low to activate the relevant device on the SPI bus
+ */
+
+ /*
+ * Data on the bus should be like
+ * |----------------+---------------------+-------------|
+ * | MOSI | MISO | Chip Select |
+ * |----------------+---------------------|-------------|
+ * | (don't care) | (don't care) | HIGH |
+ * | (reg_addr) | (don't care) | LOW |
+ * | (don't care) | (reg_data[0]) | LOW |
+ * | (....) | (....) | LOW |
+ * | (don't care) | (reg_data[len - 1]) | LOW |
+ * | (don't care) | (don't care) | HIGH |
+ * |----------------+---------------------|-------------|
+ */
+
+ return rslt;
+}
+
+int8_t user_spi_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 */
+
+ /*
+ * The parameter dev_id can be used as a variable to select which Chip Select pin has
+ * to be set low to activate the relevant device on the SPI bus
+ */
+
+ /*
+ * Data on the bus should be like
+ * |---------------------+--------------+-------------|
+ * | MOSI | MISO | Chip Select |
+ * |---------------------+--------------|-------------|
+ * | (don't care) | (don't care) | HIGH |
+ * | (reg_addr) | (don't care) | LOW |
+ * | (reg_data[0]) | (don't care) | LOW |
+ * | (....) | (....) | LOW |
+ * | (reg_data[len - 1]) | (don't care) | LOW |
+ * | (don't care) | (don't care) | HIGH |
+ * |---------------------+--------------|-------------|
+ */
+
+ return rslt;
+}
+
+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 */
+
+ /*
+ * The parameter dev_id can be used as a variable to store the I2C address of the device
+ */
+
+ /*
+ * Data on the bus should be like
+ * |------------+---------------------|
+ * | I2C action | Data |
+ * |------------+---------------------|
+ * | Start | - |
+ * | Write | (reg_addr) |
+ * | Stop | - |
+ * | Start | - |
+ * | Read | (reg_data[0]) |
+ * | Read | (....) |
+ * | Read | (reg_data[len - 1]) |
+ * | Stop | - |
+ * |------------+---------------------|
+ */
+
+ return rslt;
+}
+
+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 */
+
+ /*
+ * The parameter dev_id can be used as a variable to store the I2C address of the device
+ */
+
+ /*
+ * Data on the bus should be like
+ * |------------+---------------------|
+ * | I2C action | Data |
+ * |------------+---------------------|
+ * | Start | - |
+ * | Write | (reg_addr) |
+ * | Write | (reg_data[0]) |
+ * | Write | (....) |
+ * | Write | (reg_data[len - 1]) |
+ * | Stop | - |
+ * |------------+---------------------|
+ */
+
+ return rslt;
+}
+
+```
+
+## Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
\ No newline at end of file
diff --git a/lib/Bosch-BSEC/bme680.c b/lib/Bosch-BSEC/bme680.c
new file mode 100644
index 00000000..6067725a
--- /dev/null
+++ b/lib/Bosch-BSEC/bme680.c
@@ -0,0 +1,1367 @@
+/**\mainpage
+ * Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * Neither the name of the copyright holder nor the names of the
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+ * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
+ * OR CONTRIBUTORS BE LIABLE FOR ANY
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
+ * OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
+ *
+ * The information provided is believed to be accurate and reliable.
+ * The copyright holder assumes no responsibility
+ * for the consequences of use
+ * of such information nor for any infringement of patents or
+ * other rights of third parties which may result from its use.
+ * No license is granted by implication or otherwise under any patent or
+ * patent rights of the copyright holder.
+ *
+ * File bme680.c
+ * @date 19 Jun 2018
+ * @version 3.5.9
+ *
+ */
+
+/*! @file bme680.c
+ @brief Sensor driver for BME680 sensor */
+#include "bme680.h"
+
+/*!
+ * @brief This internal API is used to read the calibrated data from the sensor.
+ *
+ * This function is used to retrieve the calibration
+ * data from the image registers of the sensor.
+ *
+ * @note Registers 89h to A1h for calibration data 1 to 24
+ * from bit 0 to 7
+ * @note Registers E1h to F0h for calibration data 25 to 40
+ * from bit 0 to 7
+ * @param[in] dev :Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status.
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_calib_data(struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to set the gas configuration of the sensor.
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status.
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_gas_config(struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to get the gas configuration of the sensor.
+ * @note heatr_temp and heatr_dur values are currently register data
+ * and not the actual values set
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status.
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_gas_config(struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the Heat duration value.
+ *
+ * @param[in] dur :Value of the duration to be shared.
+ *
+ * @return uint8_t threshold duration after calculation.
+ */
+static uint8_t calc_heater_dur(uint16_t dur);
+
+#ifndef BME680_FLOAT_POINT_COMPENSATION
+
+/*!
+ * @brief This internal API is used to calculate the temperature value.
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] temp_adc :Contains the temperature ADC value .
+ *
+ * @return uint32_t calculated temperature.
+ */
+static int16_t calc_temperature(uint32_t temp_adc, struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the pressure value.
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] pres_adc :Contains the pressure ADC value .
+ *
+ * @return uint32_t calculated pressure.
+ */
+static uint32_t calc_pressure(uint32_t pres_adc, const struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the humidity value.
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] hum_adc :Contains the humidity ADC value.
+ *
+ * @return uint32_t calculated humidity.
+ */
+static uint32_t calc_humidity(uint16_t hum_adc, const struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the Gas Resistance value.
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] gas_res_adc :Contains the Gas Resistance ADC value.
+ * @param[in] gas_range :Contains the range of gas values.
+ *
+ * @return uint32_t calculated gas resistance.
+ */
+static uint32_t calc_gas_resistance(uint16_t gas_res_adc, uint8_t gas_range, const struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the Heat Resistance value.
+ *
+ * @param[in] dev : Structure instance of bme680_dev
+ * @param[in] temp : Contains the target temperature value.
+ *
+ * @return uint8_t calculated heater resistance.
+ */
+static uint8_t calc_heater_res(uint16_t temp, const struct bme680_dev *dev);
+
+#else
+/*!
+ * @brief This internal API is used to calculate the
+ * temperature value value in float format
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] temp_adc :Contains the temperature ADC value .
+ *
+ * @return Calculated temperature in float
+ */
+static float calc_temperature(uint32_t temp_adc, struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the
+ * pressure value value in float format
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] pres_adc :Contains the pressure ADC value .
+ *
+ * @return Calculated pressure in float.
+ */
+static float calc_pressure(uint32_t pres_adc, const struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the
+ * humidity value value in float format
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] hum_adc :Contains the humidity ADC value.
+ *
+ * @return Calculated humidity in float.
+ */
+static float calc_humidity(uint16_t hum_adc, const struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the
+ * gas resistance value value in float format
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] gas_res_adc :Contains the Gas Resistance ADC value.
+ * @param[in] gas_range :Contains the range of gas values.
+ *
+ * @return Calculated gas resistance in float.
+ */
+static float calc_gas_resistance(uint16_t gas_res_adc, uint8_t gas_range, const struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to calculate the
+ * heater resistance value in float format
+ *
+ * @param[in] temp : Contains the target temperature value.
+ * @param[in] dev : Structure instance of bme680_dev.
+ *
+ * @return Calculated heater resistance in float.
+ */
+static float calc_heater_res(uint16_t temp, const struct bme680_dev *dev);
+
+#endif
+
+/*!
+ * @brief This internal API is used to calculate the field data of sensor.
+ *
+ * @param[out] data :Structure instance to hold the data
+ * @param[in] dev :Structure instance of bme680_dev.
+ *
+ * @return int8_t result of the field data from sensor.
+ */
+static int8_t read_field_data(struct bme680_field_data *data, struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to set the memory page
+ * based on register address.
+ *
+ * The value of memory page
+ * value | Description
+ * --------|--------------
+ * 0 | BME680_PAGE0_SPI
+ * 1 | BME680_PAGE1_SPI
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ * @param[in] reg_addr :Contains the register address array.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_mem_page(uint8_t reg_addr, struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to get the memory page based
+ * on register address.
+ *
+ * The value of memory page
+ * value | Description
+ * --------|--------------
+ * 0 | BME680_PAGE0_SPI
+ * 1 | BME680_PAGE1_SPI
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_mem_page(struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to validate the device pointer for
+ * null conditions.
+ *
+ * @param[in] dev :Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t null_ptr_check(const struct bme680_dev *dev);
+
+/*!
+ * @brief This internal API is used to check the boundary
+ * conditions.
+ *
+ * @param[in] value :pointer to the value.
+ * @param[in] min :minimum value.
+ * @param[in] max :maximum value.
+ * @param[in] dev :Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t boundary_check(uint8_t *value, uint8_t min, uint8_t max, struct bme680_dev *dev);
+
+/****************** Global Function Definitions *******************************/
+/*!
+ *@brief This API is the entry point.
+ *It reads the chip-id and calibration data from the sensor.
+ */
+int8_t bme680_init(struct bme680_dev *dev)
+{
+ int8_t rslt;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ /* Soft reset to restore it to default values*/
+ rslt = bme680_soft_reset(dev);
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(BME680_CHIP_ID_ADDR, &dev->chip_id, 1, dev);
+ if (rslt == BME680_OK) {
+ if (dev->chip_id == BME680_CHIP_ID) {
+ /* Get the Calibration data */
+ rslt = get_calib_data(dev);
+ } else {
+ rslt = BME680_E_DEV_NOT_FOUND;
+ }
+ }
+ }
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API reads the data from the given register address of the sensor.
+ */
+int8_t bme680_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bme680_dev *dev)
+{
+ int8_t rslt;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ if (dev->intf == BME680_SPI_INTF) {
+ /* Set the memory page */
+ rslt = set_mem_page(reg_addr, dev);
+ if (rslt == BME680_OK)
+ reg_addr = reg_addr | BME680_SPI_RD_MSK;
+ }
+ dev->com_rslt = dev->read(dev->dev_id, reg_addr, reg_data, len);
+ if (dev->com_rslt != 0)
+ rslt = BME680_E_COM_FAIL;
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API writes the given data to the register address
+ * of the sensor.
+ */
+int8_t bme680_set_regs(const uint8_t *reg_addr, const uint8_t *reg_data, uint8_t len, struct bme680_dev *dev)
+{
+ int8_t rslt;
+ /* Length of the temporary buffer is 2*(length of register)*/
+ uint8_t tmp_buff[BME680_TMP_BUFFER_LENGTH] = { 0 };
+ uint16_t index;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ if ((len > 0) && (len < BME680_TMP_BUFFER_LENGTH / 2)) {
+ /* Interleave the 2 arrays */
+ for (index = 0; index < len; index++) {
+ if (dev->intf == BME680_SPI_INTF) {
+ /* Set the memory page */
+ rslt = set_mem_page(reg_addr[index], dev);
+ tmp_buff[(2 * index)] = reg_addr[index] & BME680_SPI_WR_MSK;
+ } else {
+ tmp_buff[(2 * index)] = reg_addr[index];
+ }
+ tmp_buff[(2 * index) + 1] = reg_data[index];
+ }
+ /* Write the interleaved array */
+ if (rslt == BME680_OK) {
+ dev->com_rslt = dev->write(dev->dev_id, tmp_buff[0], &tmp_buff[1], (2 * len) - 1);
+ if (dev->com_rslt != 0)
+ rslt = BME680_E_COM_FAIL;
+ }
+ } else {
+ rslt = BME680_E_INVALID_LENGTH;
+ }
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API performs the soft reset of the sensor.
+ */
+int8_t bme680_soft_reset(struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t reg_addr = BME680_SOFT_RESET_ADDR;
+ /* 0xb6 is the soft reset command */
+ uint8_t soft_rst_cmd = BME680_SOFT_RESET_CMD;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ if (dev->intf == BME680_SPI_INTF)
+ rslt = get_mem_page(dev);
+
+ /* Reset the device */
+ if (rslt == BME680_OK) {
+ rslt = bme680_set_regs(®_addr, &soft_rst_cmd, 1, dev);
+ /* Wait for 5ms */
+ dev->delay_ms(BME680_RESET_PERIOD);
+
+ if (rslt == BME680_OK) {
+ /* After reset get the memory page */
+ if (dev->intf == BME680_SPI_INTF)
+ rslt = get_mem_page(dev);
+ }
+ }
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API is used to set the oversampling, filter and T,P,H, gas selection
+ * settings in the sensor.
+ */
+int8_t bme680_set_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t reg_addr;
+ uint8_t data = 0;
+ uint8_t count = 0;
+ uint8_t reg_array[BME680_REG_BUFFER_LENGTH] = { 0 };
+ uint8_t data_array[BME680_REG_BUFFER_LENGTH] = { 0 };
+ uint8_t intended_power_mode = dev->power_mode; /* Save intended power mode */
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ if (desired_settings & BME680_GAS_MEAS_SEL)
+ rslt = set_gas_config(dev);
+
+ dev->power_mode = BME680_SLEEP_MODE;
+ if (rslt == BME680_OK)
+ rslt = bme680_set_sensor_mode(dev);
+
+ /* Selecting the filter */
+ if (desired_settings & BME680_FILTER_SEL) {
+ rslt = boundary_check(&dev->tph_sett.filter, BME680_FILTER_SIZE_0, BME680_FILTER_SIZE_127, dev);
+ reg_addr = BME680_CONF_ODR_FILT_ADDR;
+
+ if (rslt == BME680_OK)
+ rslt = bme680_get_regs(reg_addr, &data, 1, dev);
+
+ if (desired_settings & BME680_FILTER_SEL)
+ data = BME680_SET_BITS(data, BME680_FILTER, dev->tph_sett.filter);
+
+ reg_array[count] = reg_addr; /* Append configuration */
+ data_array[count] = data;
+ count++;
+ }
+
+ /* Selecting heater control for the sensor */
+ if (desired_settings & BME680_HCNTRL_SEL) {
+ rslt = boundary_check(&dev->gas_sett.heatr_ctrl, BME680_ENABLE_HEATER,
+ BME680_DISABLE_HEATER, dev);
+ reg_addr = BME680_CONF_HEAT_CTRL_ADDR;
+
+ if (rslt == BME680_OK)
+ rslt = bme680_get_regs(reg_addr, &data, 1, dev);
+ data = BME680_SET_BITS_POS_0(data, BME680_HCTRL, dev->gas_sett.heatr_ctrl);
+
+ reg_array[count] = reg_addr; /* Append configuration */
+ data_array[count] = data;
+ count++;
+ }
+
+ /* Selecting heater T,P oversampling for the sensor */
+ if (desired_settings & (BME680_OST_SEL | BME680_OSP_SEL)) {
+ rslt = boundary_check(&dev->tph_sett.os_temp, BME680_OS_NONE, BME680_OS_16X, dev);
+ reg_addr = BME680_CONF_T_P_MODE_ADDR;
+
+ if (rslt == BME680_OK)
+ rslt = bme680_get_regs(reg_addr, &data, 1, dev);
+
+ if (desired_settings & BME680_OST_SEL)
+ data = BME680_SET_BITS(data, BME680_OST, dev->tph_sett.os_temp);
+
+ if (desired_settings & BME680_OSP_SEL)
+ data = BME680_SET_BITS(data, BME680_OSP, dev->tph_sett.os_pres);
+
+ reg_array[count] = reg_addr;
+ data_array[count] = data;
+ count++;
+ }
+
+ /* Selecting humidity oversampling for the sensor */
+ if (desired_settings & BME680_OSH_SEL) {
+ rslt = boundary_check(&dev->tph_sett.os_hum, BME680_OS_NONE, BME680_OS_16X, dev);
+ reg_addr = BME680_CONF_OS_H_ADDR;
+
+ if (rslt == BME680_OK)
+ rslt = bme680_get_regs(reg_addr, &data, 1, dev);
+ data = BME680_SET_BITS_POS_0(data, BME680_OSH, dev->tph_sett.os_hum);
+
+ reg_array[count] = reg_addr; /* Append configuration */
+ data_array[count] = data;
+ count++;
+ }
+
+ /* Selecting the runGas and NB conversion settings for the sensor */
+ if (desired_settings & (BME680_RUN_GAS_SEL | BME680_NBCONV_SEL)) {
+ rslt = boundary_check(&dev->gas_sett.run_gas, BME680_RUN_GAS_DISABLE,
+ BME680_RUN_GAS_ENABLE, dev);
+ if (rslt == BME680_OK) {
+ /* Validate boundary conditions */
+ rslt = boundary_check(&dev->gas_sett.nb_conv, BME680_NBCONV_MIN,
+ BME680_NBCONV_MAX, dev);
+ }
+
+ reg_addr = BME680_CONF_ODR_RUN_GAS_NBC_ADDR;
+
+ if (rslt == BME680_OK)
+ rslt = bme680_get_regs(reg_addr, &data, 1, dev);
+
+ if (desired_settings & BME680_RUN_GAS_SEL)
+ data = BME680_SET_BITS(data, BME680_RUN_GAS, dev->gas_sett.run_gas);
+
+ if (desired_settings & BME680_NBCONV_SEL)
+ data = BME680_SET_BITS_POS_0(data, BME680_NBCONV, dev->gas_sett.nb_conv);
+
+ reg_array[count] = reg_addr; /* Append configuration */
+ data_array[count] = data;
+ count++;
+ }
+
+ if (rslt == BME680_OK)
+ rslt = bme680_set_regs(reg_array, data_array, count, dev);
+
+ /* Restore previous intended power mode */
+ dev->power_mode = intended_power_mode;
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API is used to get the oversampling, filter and T,P,H, gas selection
+ * settings in the sensor.
+ */
+int8_t bme680_get_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev)
+{
+ int8_t rslt;
+ /* starting address of the register array for burst read*/
+ uint8_t reg_addr = BME680_CONF_HEAT_CTRL_ADDR;
+ uint8_t data_array[BME680_REG_BUFFER_LENGTH] = { 0 };
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(reg_addr, data_array, BME680_REG_BUFFER_LENGTH, dev);
+
+ if (rslt == BME680_OK) {
+ if (desired_settings & BME680_GAS_MEAS_SEL)
+ rslt = get_gas_config(dev);
+
+ /* get the T,P,H ,Filter,ODR settings here */
+ if (desired_settings & BME680_FILTER_SEL)
+ dev->tph_sett.filter = BME680_GET_BITS(data_array[BME680_REG_FILTER_INDEX],
+ BME680_FILTER);
+
+ if (desired_settings & (BME680_OST_SEL | BME680_OSP_SEL)) {
+ dev->tph_sett.os_temp = BME680_GET_BITS(data_array[BME680_REG_TEMP_INDEX], BME680_OST);
+ dev->tph_sett.os_pres = BME680_GET_BITS(data_array[BME680_REG_PRES_INDEX], BME680_OSP);
+ }
+
+ if (desired_settings & BME680_OSH_SEL)
+ dev->tph_sett.os_hum = BME680_GET_BITS_POS_0(data_array[BME680_REG_HUM_INDEX],
+ BME680_OSH);
+
+ /* get the gas related settings */
+ if (desired_settings & BME680_HCNTRL_SEL)
+ dev->gas_sett.heatr_ctrl = BME680_GET_BITS_POS_0(data_array[BME680_REG_HCTRL_INDEX],
+ BME680_HCTRL);
+
+ if (desired_settings & (BME680_RUN_GAS_SEL | BME680_NBCONV_SEL)) {
+ dev->gas_sett.nb_conv = BME680_GET_BITS_POS_0(data_array[BME680_REG_NBCONV_INDEX],
+ BME680_NBCONV);
+ dev->gas_sett.run_gas = BME680_GET_BITS(data_array[BME680_REG_RUN_GAS_INDEX],
+ BME680_RUN_GAS);
+ }
+ }
+ } else {
+ rslt = BME680_E_NULL_PTR;
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API is used to set the power mode of the sensor.
+ */
+int8_t bme680_set_sensor_mode(struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t tmp_pow_mode;
+ uint8_t pow_mode = 0;
+ uint8_t reg_addr = BME680_CONF_T_P_MODE_ADDR;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ /* Call repeatedly until in sleep */
+ do {
+ rslt = bme680_get_regs(BME680_CONF_T_P_MODE_ADDR, &tmp_pow_mode, 1, dev);
+ if (rslt == BME680_OK) {
+ /* Put to sleep before changing mode */
+ pow_mode = (tmp_pow_mode & BME680_MODE_MSK);
+
+ if (pow_mode != BME680_SLEEP_MODE) {
+ tmp_pow_mode = tmp_pow_mode & (~BME680_MODE_MSK); /* Set to sleep */
+ rslt = bme680_set_regs(®_addr, &tmp_pow_mode, 1, dev);
+ dev->delay_ms(BME680_POLL_PERIOD_MS);
+ }
+ }
+ } while (pow_mode != BME680_SLEEP_MODE);
+
+ /* Already in sleep */
+ if (dev->power_mode != BME680_SLEEP_MODE) {
+ tmp_pow_mode = (tmp_pow_mode & ~BME680_MODE_MSK) | (dev->power_mode & BME680_MODE_MSK);
+ if (rslt == BME680_OK)
+ rslt = bme680_set_regs(®_addr, &tmp_pow_mode, 1, dev);
+ }
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API is used to get the power mode of the sensor.
+ */
+int8_t bme680_get_sensor_mode(struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t mode;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(BME680_CONF_T_P_MODE_ADDR, &mode, 1, dev);
+ /* Masking the other register bit info*/
+ dev->power_mode = mode & BME680_MODE_MSK;
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This API is used to set the profile duration of the sensor.
+ */
+void bme680_set_profile_dur(uint16_t duration, struct bme680_dev *dev)
+{
+ uint32_t tph_dur; /* Calculate in us */
+ uint32_t meas_cycles;
+ uint8_t os_to_meas_cycles[6] = {0, 1, 2, 4, 8, 16};
+
+ meas_cycles = os_to_meas_cycles[dev->tph_sett.os_temp];
+ meas_cycles += os_to_meas_cycles[dev->tph_sett.os_pres];
+ meas_cycles += os_to_meas_cycles[dev->tph_sett.os_hum];
+
+ /* TPH measurement duration */
+ tph_dur = meas_cycles * UINT32_C(1963);
+ tph_dur += UINT32_C(477 * 4); /* TPH switching duration */
+ tph_dur += UINT32_C(477 * 5); /* Gas measurement duration */
+ tph_dur += UINT32_C(500); /* Get it to the closest whole number.*/
+ tph_dur /= UINT32_C(1000); /* Convert to ms */
+
+ tph_dur += UINT32_C(1); /* Wake up duration of 1ms */
+ /* The remaining time should be used for heating */
+ dev->gas_sett.heatr_dur = duration - (uint16_t) tph_dur;
+}
+
+/*!
+ * @brief This API is used to get the profile duration of the sensor.
+ */
+void bme680_get_profile_dur(uint16_t *duration, const struct bme680_dev *dev)
+{
+ uint32_t tph_dur; /* Calculate in us */
+ uint32_t meas_cycles;
+ uint8_t os_to_meas_cycles[6] = {0, 1, 2, 4, 8, 16};
+
+ meas_cycles = os_to_meas_cycles[dev->tph_sett.os_temp];
+ meas_cycles += os_to_meas_cycles[dev->tph_sett.os_pres];
+ meas_cycles += os_to_meas_cycles[dev->tph_sett.os_hum];
+
+ /* TPH measurement duration */
+ tph_dur = meas_cycles * UINT32_C(1963);
+ tph_dur += UINT32_C(477 * 4); /* TPH switching duration */
+ tph_dur += UINT32_C(477 * 5); /* Gas measurement duration */
+ tph_dur += UINT32_C(500); /* Get it to the closest whole number.*/
+ tph_dur /= UINT32_C(1000); /* Convert to ms */
+
+ tph_dur += UINT32_C(1); /* Wake up duration of 1ms */
+
+ *duration = (uint16_t) tph_dur;
+
+ /* Get the gas duration only when the run gas is enabled */
+ if (dev->gas_sett.run_gas) {
+ /* The remaining time should be used for heating */
+ *duration += dev->gas_sett.heatr_dur;
+ }
+}
+
+/*!
+ * @brief This API reads the pressure, temperature and humidity and gas data
+ * from the sensor, compensates the data and store it in the bme680_data
+ * structure instance passed by the user.
+ */
+int8_t bme680_get_sensor_data(struct bme680_field_data *data, struct bme680_dev *dev)
+{
+ int8_t rslt;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ /* Reading the sensor data in forced mode only */
+ rslt = read_field_data(data, dev);
+ if (rslt == BME680_OK) {
+ if (data->status & BME680_NEW_DATA_MSK)
+ dev->new_fields = 1;
+ else
+ dev->new_fields = 0;
+ }
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This internal API is used to read the calibrated data from the sensor.
+ */
+static int8_t get_calib_data(struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t coeff_array[BME680_COEFF_SIZE] = { 0 };
+ uint8_t temp_var = 0; /* Temporary variable */
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(BME680_COEFF_ADDR1, coeff_array, BME680_COEFF_ADDR1_LEN, dev);
+ /* Append the second half in the same array */
+ if (rslt == BME680_OK)
+ rslt = bme680_get_regs(BME680_COEFF_ADDR2, &coeff_array[BME680_COEFF_ADDR1_LEN]
+ , BME680_COEFF_ADDR2_LEN, dev);
+
+ /* Temperature related coefficients */
+ dev->calib.par_t1 = (uint16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_T1_MSB_REG],
+ coeff_array[BME680_T1_LSB_REG]));
+ dev->calib.par_t2 = (int16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_T2_MSB_REG],
+ coeff_array[BME680_T2_LSB_REG]));
+ dev->calib.par_t3 = (int8_t) (coeff_array[BME680_T3_REG]);
+
+ /* Pressure related coefficients */
+ dev->calib.par_p1 = (uint16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_P1_MSB_REG],
+ coeff_array[BME680_P1_LSB_REG]));
+ dev->calib.par_p2 = (int16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_P2_MSB_REG],
+ coeff_array[BME680_P2_LSB_REG]));
+ dev->calib.par_p3 = (int8_t) coeff_array[BME680_P3_REG];
+ dev->calib.par_p4 = (int16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_P4_MSB_REG],
+ coeff_array[BME680_P4_LSB_REG]));
+ dev->calib.par_p5 = (int16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_P5_MSB_REG],
+ coeff_array[BME680_P5_LSB_REG]));
+ dev->calib.par_p6 = (int8_t) (coeff_array[BME680_P6_REG]);
+ dev->calib.par_p7 = (int8_t) (coeff_array[BME680_P7_REG]);
+ dev->calib.par_p8 = (int16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_P8_MSB_REG],
+ coeff_array[BME680_P8_LSB_REG]));
+ dev->calib.par_p9 = (int16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_P9_MSB_REG],
+ coeff_array[BME680_P9_LSB_REG]));
+ dev->calib.par_p10 = (uint8_t) (coeff_array[BME680_P10_REG]);
+
+ /* Humidity related coefficients */
+ dev->calib.par_h1 = (uint16_t) (((uint16_t) coeff_array[BME680_H1_MSB_REG] << BME680_HUM_REG_SHIFT_VAL)
+ | (coeff_array[BME680_H1_LSB_REG] & BME680_BIT_H1_DATA_MSK));
+ dev->calib.par_h2 = (uint16_t) (((uint16_t) coeff_array[BME680_H2_MSB_REG] << BME680_HUM_REG_SHIFT_VAL)
+ | ((coeff_array[BME680_H2_LSB_REG]) >> BME680_HUM_REG_SHIFT_VAL));
+ dev->calib.par_h3 = (int8_t) coeff_array[BME680_H3_REG];
+ dev->calib.par_h4 = (int8_t) coeff_array[BME680_H4_REG];
+ dev->calib.par_h5 = (int8_t) coeff_array[BME680_H5_REG];
+ dev->calib.par_h6 = (uint8_t) coeff_array[BME680_H6_REG];
+ dev->calib.par_h7 = (int8_t) coeff_array[BME680_H7_REG];
+
+ /* Gas heater related coefficients */
+ dev->calib.par_gh1 = (int8_t) coeff_array[BME680_GH1_REG];
+ dev->calib.par_gh2 = (int16_t) (BME680_CONCAT_BYTES(coeff_array[BME680_GH2_MSB_REG],
+ coeff_array[BME680_GH2_LSB_REG]));
+ dev->calib.par_gh3 = (int8_t) coeff_array[BME680_GH3_REG];
+
+ /* Other coefficients */
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(BME680_ADDR_RES_HEAT_RANGE_ADDR, &temp_var, 1, dev);
+
+ dev->calib.res_heat_range = ((temp_var & BME680_RHRANGE_MSK) / 16);
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(BME680_ADDR_RES_HEAT_VAL_ADDR, &temp_var, 1, dev);
+
+ dev->calib.res_heat_val = (int8_t) temp_var;
+ if (rslt == BME680_OK)
+ rslt = bme680_get_regs(BME680_ADDR_RANGE_SW_ERR_ADDR, &temp_var, 1, dev);
+ }
+ }
+ dev->calib.range_sw_err = ((int8_t) temp_var & (int8_t) BME680_RSERROR_MSK) / 16;
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This internal API is used to set the gas configuration of the sensor.
+ */
+static int8_t set_gas_config(struct bme680_dev *dev)
+{
+ int8_t rslt;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+
+ uint8_t reg_addr[2] = {0};
+ uint8_t reg_data[2] = {0};
+
+ if (dev->power_mode == BME680_FORCED_MODE) {
+ reg_addr[0] = BME680_RES_HEAT0_ADDR;
+ reg_data[0] = calc_heater_res(dev->gas_sett.heatr_temp, dev);
+ reg_addr[1] = BME680_GAS_WAIT0_ADDR;
+ reg_data[1] = calc_heater_dur(dev->gas_sett.heatr_dur);
+ dev->gas_sett.nb_conv = 0;
+ } else {
+ rslt = BME680_W_DEFINE_PWR_MODE;
+ }
+ if (rslt == BME680_OK)
+ rslt = bme680_set_regs(reg_addr, reg_data, 2, dev);
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This internal API is used to get the gas configuration of the sensor.
+ * @note heatr_temp and heatr_dur values are currently register data
+ * and not the actual values set
+ */
+static int8_t get_gas_config(struct bme680_dev *dev)
+{
+ int8_t rslt;
+ /* starting address of the register array for burst read*/
+ uint8_t reg_addr1 = BME680_ADDR_SENS_CONF_START;
+ uint8_t reg_addr2 = BME680_ADDR_GAS_CONF_START;
+ uint8_t reg_data = 0;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ if (BME680_SPI_INTF == dev->intf) {
+ /* Memory page switch the SPI address*/
+ rslt = set_mem_page(reg_addr1, dev);
+ }
+
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(reg_addr1, ®_data, 1, dev);
+ if (rslt == BME680_OK) {
+ dev->gas_sett.heatr_temp = reg_data;
+ rslt = bme680_get_regs(reg_addr2, ®_data, 1, dev);
+ if (rslt == BME680_OK) {
+ /* Heating duration register value */
+ dev->gas_sett.heatr_dur = reg_data;
+ }
+ }
+ }
+ }
+
+ return rslt;
+}
+
+#ifndef BME680_FLOAT_POINT_COMPENSATION
+
+/*!
+ * @brief This internal API is used to calculate the temperature value.
+ */
+static int16_t calc_temperature(uint32_t temp_adc, struct bme680_dev *dev)
+{
+ int64_t var1;
+ int64_t var2;
+ int64_t var3;
+ int16_t calc_temp;
+
+ var1 = ((int32_t) temp_adc >> 3) - ((int32_t) dev->calib.par_t1 << 1);
+ var2 = (var1 * (int32_t) dev->calib.par_t2) >> 11;
+ var3 = ((var1 >> 1) * (var1 >> 1)) >> 12;
+ var3 = ((var3) * ((int32_t) dev->calib.par_t3 << 4)) >> 14;
+ dev->calib.t_fine = (int32_t) (var2 + var3);
+ calc_temp = (int16_t) (((dev->calib.t_fine * 5) + 128) >> 8);
+
+ return calc_temp;
+}
+
+/*!
+ * @brief This internal API is used to calculate the pressure value.
+ */
+static uint32_t calc_pressure(uint32_t pres_adc, const struct bme680_dev *dev)
+{
+ int32_t var1;
+ int32_t var2;
+ int32_t var3;
+ int32_t pressure_comp;
+
+ var1 = (((int32_t)dev->calib.t_fine) >> 1) - 64000;
+ var2 = ((((var1 >> 2) * (var1 >> 2)) >> 11) *
+ (int32_t)dev->calib.par_p6) >> 2;
+ var2 = var2 + ((var1 * (int32_t)dev->calib.par_p5) << 1);
+ var2 = (var2 >> 2) + ((int32_t)dev->calib.par_p4 << 16);
+ var1 = (((((var1 >> 2) * (var1 >> 2)) >> 13) *
+ ((int32_t)dev->calib.par_p3 << 5)) >> 3) +
+ (((int32_t)dev->calib.par_p2 * var1) >> 1);
+ var1 = var1 >> 18;
+ var1 = ((32768 + var1) * (int32_t)dev->calib.par_p1) >> 15;
+ pressure_comp = 1048576 - pres_adc;
+ pressure_comp = (int32_t)((pressure_comp - (var2 >> 12)) * ((uint32_t)3125));
+ if (pressure_comp >= BME680_MAX_OVERFLOW_VAL)
+ pressure_comp = ((pressure_comp / var1) << 1);
+ else
+ pressure_comp = ((pressure_comp << 1) / var1);
+ var1 = ((int32_t)dev->calib.par_p9 * (int32_t)(((pressure_comp >> 3) *
+ (pressure_comp >> 3)) >> 13)) >> 12;
+ var2 = ((int32_t)(pressure_comp >> 2) *
+ (int32_t)dev->calib.par_p8) >> 13;
+ var3 = ((int32_t)(pressure_comp >> 8) * (int32_t)(pressure_comp >> 8) *
+ (int32_t)(pressure_comp >> 8) *
+ (int32_t)dev->calib.par_p10) >> 17;
+
+ pressure_comp = (int32_t)(pressure_comp) + ((var1 + var2 + var3 +
+ ((int32_t)dev->calib.par_p7 << 7)) >> 4);
+
+ return (uint32_t)pressure_comp;
+
+}
+
+/*!
+ * @brief This internal API is used to calculate the humidity value.
+ */
+static uint32_t calc_humidity(uint16_t hum_adc, const struct bme680_dev *dev)
+{
+ int32_t var1;
+ int32_t var2;
+ int32_t var3;
+ int32_t var4;
+ int32_t var5;
+ int32_t var6;
+ int32_t temp_scaled;
+ int32_t calc_hum;
+
+ temp_scaled = (((int32_t) dev->calib.t_fine * 5) + 128) >> 8;
+ var1 = (int32_t) (hum_adc - ((int32_t) ((int32_t) dev->calib.par_h1 * 16)))
+ - (((temp_scaled * (int32_t) dev->calib.par_h3) / ((int32_t) 100)) >> 1);
+ var2 = ((int32_t) dev->calib.par_h2
+ * (((temp_scaled * (int32_t) dev->calib.par_h4) / ((int32_t) 100))
+ + (((temp_scaled * ((temp_scaled * (int32_t) dev->calib.par_h5) / ((int32_t) 100))) >> 6)
+ / ((int32_t) 100)) + (int32_t) (1 << 14))) >> 10;
+ var3 = var1 * var2;
+ var4 = (int32_t) dev->calib.par_h6 << 7;
+ var4 = ((var4) + ((temp_scaled * (int32_t) dev->calib.par_h7) / ((int32_t) 100))) >> 4;
+ var5 = ((var3 >> 14) * (var3 >> 14)) >> 10;
+ var6 = (var4 * var5) >> 1;
+ calc_hum = (((var3 + var6) >> 10) * ((int32_t) 1000)) >> 12;
+
+ if (calc_hum > 100000) /* Cap at 100%rH */
+ calc_hum = 100000;
+ else if (calc_hum < 0)
+ calc_hum = 0;
+
+ return (uint32_t) calc_hum;
+}
+
+/*!
+ * @brief This internal API is used to calculate the Gas Resistance value.
+ */
+static uint32_t calc_gas_resistance(uint16_t gas_res_adc, uint8_t gas_range, const struct bme680_dev *dev)
+{
+ int64_t var1;
+ uint64_t var2;
+ int64_t var3;
+ uint32_t calc_gas_res;
+ /**Look up table 1 for the possible gas range values */
+ uint32_t lookupTable1[16] = { UINT32_C(2147483647), UINT32_C(2147483647), UINT32_C(2147483647), UINT32_C(2147483647),
+ UINT32_C(2147483647), UINT32_C(2126008810), UINT32_C(2147483647), UINT32_C(2130303777),
+ UINT32_C(2147483647), UINT32_C(2147483647), UINT32_C(2143188679), UINT32_C(2136746228),
+ UINT32_C(2147483647), UINT32_C(2126008810), UINT32_C(2147483647), UINT32_C(2147483647) };
+ /**Look up table 2 for the possible gas range values */
+ uint32_t lookupTable2[16] = { UINT32_C(4096000000), UINT32_C(2048000000), UINT32_C(1024000000), UINT32_C(512000000),
+ UINT32_C(255744255), UINT32_C(127110228), UINT32_C(64000000), UINT32_C(32258064), UINT32_C(16016016),
+ UINT32_C(8000000), UINT32_C(4000000), UINT32_C(2000000), UINT32_C(1000000), UINT32_C(500000),
+ UINT32_C(250000), UINT32_C(125000) };
+
+ var1 = (int64_t) ((1340 + (5 * (int64_t) dev->calib.range_sw_err)) *
+ ((int64_t) lookupTable1[gas_range])) >> 16;
+ var2 = (((int64_t) ((int64_t) gas_res_adc << 15) - (int64_t) (16777216)) + var1);
+ var3 = (((int64_t) lookupTable2[gas_range] * (int64_t) var1) >> 9);
+ calc_gas_res = (uint32_t) ((var3 + ((int64_t) var2 >> 1)) / (int64_t) var2);
+
+ return calc_gas_res;
+}
+
+/*!
+ * @brief This internal API is used to calculate the Heat Resistance value.
+ */
+static uint8_t calc_heater_res(uint16_t temp, const struct bme680_dev *dev)
+{
+ uint8_t heatr_res;
+ int32_t var1;
+ int32_t var2;
+ int32_t var3;
+ int32_t var4;
+ int32_t var5;
+ int32_t heatr_res_x100;
+
+ if (temp > 400) /* Cap temperature */
+ temp = 400;
+
+ var1 = (((int32_t) dev->amb_temp * dev->calib.par_gh3) / 1000) * 256;
+ var2 = (dev->calib.par_gh1 + 784) * (((((dev->calib.par_gh2 + 154009) * temp * 5) / 100) + 3276800) / 10);
+ var3 = var1 + (var2 / 2);
+ var4 = (var3 / (dev->calib.res_heat_range + 4));
+ var5 = (131 * dev->calib.res_heat_val) + 65536;
+ heatr_res_x100 = (int32_t) (((var4 / var5) - 250) * 34);
+ heatr_res = (uint8_t) ((heatr_res_x100 + 50) / 100);
+
+ return heatr_res;
+}
+
+#else
+
+
+/*!
+ * @brief This internal API is used to calculate the
+ * temperature value in float format
+ */
+static float calc_temperature(uint32_t temp_adc, struct bme680_dev *dev)
+{
+ float var1 = 0;
+ float var2 = 0;
+ float calc_temp = 0;
+
+ /* calculate var1 data */
+ var1 = ((((float)temp_adc / 16384.0f) - ((float)dev->calib.par_t1 / 1024.0f))
+ * ((float)dev->calib.par_t2));
+
+ /* calculate var2 data */
+ var2 = (((((float)temp_adc / 131072.0f) - ((float)dev->calib.par_t1 / 8192.0f)) *
+ (((float)temp_adc / 131072.0f) - ((float)dev->calib.par_t1 / 8192.0f))) *
+ ((float)dev->calib.par_t3 * 16.0f));
+
+ /* t_fine value*/
+ dev->calib.t_fine = (var1 + var2);
+
+ /* compensated temperature data*/
+ calc_temp = ((dev->calib.t_fine) / 5120.0f);
+
+ return calc_temp;
+}
+
+/*!
+ * @brief This internal API is used to calculate the
+ * pressure value in float format
+ */
+static float calc_pressure(uint32_t pres_adc, const struct bme680_dev *dev)
+{
+ float var1 = 0;
+ float var2 = 0;
+ float var3 = 0;
+ float calc_pres = 0;
+
+ var1 = (((float)dev->calib.t_fine / 2.0f) - 64000.0f);
+ var2 = var1 * var1 * (((float)dev->calib.par_p6) / (131072.0f));
+ var2 = var2 + (var1 * ((float)dev->calib.par_p5) * 2.0f);
+ var2 = (var2 / 4.0f) + (((float)dev->calib.par_p4) * 65536.0f);
+ var1 = (((((float)dev->calib.par_p3 * var1 * var1) / 16384.0f)
+ + ((float)dev->calib.par_p2 * var1)) / 524288.0f);
+ var1 = ((1.0f + (var1 / 32768.0f)) * ((float)dev->calib.par_p1));
+ calc_pres = (1048576.0f - ((float)pres_adc));
+
+ /* Avoid exception caused by division by zero */
+ if ((int)var1 != 0) {
+ calc_pres = (((calc_pres - (var2 / 4096.0f)) * 6250.0f) / var1);
+ var1 = (((float)dev->calib.par_p9) * calc_pres * calc_pres) / 2147483648.0f;
+ var2 = calc_pres * (((float)dev->calib.par_p8) / 32768.0f);
+ var3 = ((calc_pres / 256.0f) * (calc_pres / 256.0f) * (calc_pres / 256.0f)
+ * (dev->calib.par_p10 / 131072.0f));
+ calc_pres = (calc_pres + (var1 + var2 + var3 + ((float)dev->calib.par_p7 * 128.0f)) / 16.0f);
+ } else {
+ calc_pres = 0;
+ }
+
+ return calc_pres;
+}
+
+/*!
+ * @brief This internal API is used to calculate the
+ * humidity value in float format
+ */
+static float calc_humidity(uint16_t hum_adc, const struct bme680_dev *dev)
+{
+ float calc_hum = 0;
+ float var1 = 0;
+ float var2 = 0;
+ float var3 = 0;
+ float var4 = 0;
+ float temp_comp;
+
+ /* compensated temperature data*/
+ temp_comp = ((dev->calib.t_fine) / 5120.0f);
+
+ var1 = (float)((float)hum_adc) - (((float)dev->calib.par_h1 * 16.0f) + (((float)dev->calib.par_h3 / 2.0f)
+ * temp_comp));
+
+ var2 = var1 * ((float)(((float) dev->calib.par_h2 / 262144.0f) * (1.0f + (((float)dev->calib.par_h4 / 16384.0f)
+ * temp_comp) + (((float)dev->calib.par_h5 / 1048576.0f) * temp_comp * temp_comp))));
+
+ var3 = (float) dev->calib.par_h6 / 16384.0f;
+
+ var4 = (float) dev->calib.par_h7 / 2097152.0f;
+
+ calc_hum = var2 + ((var3 + (var4 * temp_comp)) * var2 * var2);
+
+ if (calc_hum > 100.0f)
+ calc_hum = 100.0f;
+ else if (calc_hum < 0.0f)
+ calc_hum = 0.0f;
+
+ return calc_hum;
+}
+
+/*!
+ * @brief This internal API is used to calculate the
+ * gas resistance value in float format
+ */
+static float calc_gas_resistance(uint16_t gas_res_adc, uint8_t gas_range, const struct bme680_dev *dev)
+{
+ float calc_gas_res;
+ float var1 = 0;
+ float var2 = 0;
+ float var3 = 0;
+
+ const float lookup_k1_range[16] = {
+ 0.0, 0.0, 0.0, 0.0, 0.0, -1.0, 0.0, -0.8,
+ 0.0, 0.0, -0.2, -0.5, 0.0, -1.0, 0.0, 0.0};
+ const float lookup_k2_range[16] = {
+ 0.0, 0.0, 0.0, 0.0, 0.1, 0.7, 0.0, -0.8,
+ -0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
+
+ var1 = (1340.0f + (5.0f * dev->calib.range_sw_err));
+ var2 = (var1) * (1.0f + lookup_k1_range[gas_range]/100.0f);
+ var3 = 1.0f + (lookup_k2_range[gas_range]/100.0f);
+
+ calc_gas_res = 1.0f / (float)(var3 * (0.000000125f) * (float)(1 << gas_range) * (((((float)gas_res_adc)
+ - 512.0f)/var2) + 1.0f));
+
+ return calc_gas_res;
+}
+
+/*!
+ * @brief This internal API is used to calculate the
+ * heater resistance value in float format
+ */
+static float calc_heater_res(uint16_t temp, const struct bme680_dev *dev)
+{
+ float var1 = 0;
+ float var2 = 0;
+ float var3 = 0;
+ float var4 = 0;
+ float var5 = 0;
+ float res_heat = 0;
+
+ if (temp > 400) /* Cap temperature */
+ temp = 400;
+
+ var1 = (((float)dev->calib.par_gh1 / (16.0f)) + 49.0f);
+ var2 = ((((float)dev->calib.par_gh2 / (32768.0f)) * (0.0005f)) + 0.00235f);
+ var3 = ((float)dev->calib.par_gh3 / (1024.0f));
+ var4 = (var1 * (1.0f + (var2 * (float)temp)));
+ var5 = (var4 + (var3 * (float)dev->amb_temp));
+ res_heat = (uint8_t)(3.4f * ((var5 * (4 / (4 + (float)dev->calib.res_heat_range)) *
+ (1/(1 + ((float) dev->calib.res_heat_val * 0.002f)))) - 25));
+
+ return res_heat;
+}
+
+#endif
+
+/*!
+ * @brief This internal API is used to calculate the Heat duration value.
+ */
+static uint8_t calc_heater_dur(uint16_t dur)
+{
+ uint8_t factor = 0;
+ uint8_t durval;
+
+ if (dur >= 0xfc0) {
+ durval = 0xff; /* Max duration*/
+ } else {
+ while (dur > 0x3F) {
+ dur = dur / 4;
+ factor += 1;
+ }
+ durval = (uint8_t) (dur + (factor * 64));
+ }
+
+ return durval;
+}
+
+/*!
+ * @brief This internal API is used to calculate the field data of sensor.
+ */
+static int8_t read_field_data(struct bme680_field_data *data, struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t buff[BME680_FIELD_LENGTH] = { 0 };
+ uint8_t gas_range;
+ uint32_t adc_temp;
+ uint32_t adc_pres;
+ uint16_t adc_hum;
+ uint16_t adc_gas_res;
+ uint8_t tries = 10;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ do {
+ if (rslt == BME680_OK) {
+ rslt = bme680_get_regs(((uint8_t) (BME680_FIELD0_ADDR)), buff, (uint16_t) BME680_FIELD_LENGTH,
+ dev);
+
+ data->status = buff[0] & BME680_NEW_DATA_MSK;
+ data->gas_index = buff[0] & BME680_GAS_INDEX_MSK;
+ data->meas_index = buff[1];
+
+ /* read the raw data from the sensor */
+ adc_pres = (uint32_t) (((uint32_t) buff[2] * 4096) | ((uint32_t) buff[3] * 16)
+ | ((uint32_t) buff[4] / 16));
+ adc_temp = (uint32_t) (((uint32_t) buff[5] * 4096) | ((uint32_t) buff[6] * 16)
+ | ((uint32_t) buff[7] / 16));
+ adc_hum = (uint16_t) (((uint32_t) buff[8] * 256) | (uint32_t) buff[9]);
+ adc_gas_res = (uint16_t) ((uint32_t) buff[13] * 4 | (((uint32_t) buff[14]) / 64));
+ gas_range = buff[14] & BME680_GAS_RANGE_MSK;
+
+ data->status |= buff[14] & BME680_GASM_VALID_MSK;
+ data->status |= buff[14] & BME680_HEAT_STAB_MSK;
+
+ if (data->status & BME680_NEW_DATA_MSK) {
+ data->temperature = calc_temperature(adc_temp, dev);
+ data->pressure = calc_pressure(adc_pres, dev);
+ data->humidity = calc_humidity(adc_hum, dev);
+ data->gas_resistance = calc_gas_resistance(adc_gas_res, gas_range, dev);
+ break;
+ }
+ /* Delay to poll the data */
+ dev->delay_ms(BME680_POLL_PERIOD_MS);
+ }
+ tries--;
+ } while (tries);
+
+ if (!tries)
+ rslt = BME680_W_NO_NEW_DATA;
+
+ return rslt;
+}
+
+/*!
+ * @brief This internal API is used to set the memory page based on register address.
+ */
+static int8_t set_mem_page(uint8_t reg_addr, struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t reg;
+ uint8_t mem_page;
+
+ /* Check for null pointers in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ if (reg_addr > 0x7f)
+ mem_page = BME680_MEM_PAGE1;
+ else
+ mem_page = BME680_MEM_PAGE0;
+
+ if (mem_page != dev->mem_page) {
+ dev->mem_page = mem_page;
+
+ dev->com_rslt = dev->read(dev->dev_id, BME680_MEM_PAGE_ADDR | BME680_SPI_RD_MSK, ®, 1);
+ if (dev->com_rslt != 0)
+ rslt = BME680_E_COM_FAIL;
+
+ if (rslt == BME680_OK) {
+ reg = reg & (~BME680_MEM_PAGE_MSK);
+ reg = reg | (dev->mem_page & BME680_MEM_PAGE_MSK);
+
+ dev->com_rslt = dev->write(dev->dev_id, BME680_MEM_PAGE_ADDR & BME680_SPI_WR_MSK,
+ ®, 1);
+ if (dev->com_rslt != 0)
+ rslt = BME680_E_COM_FAIL;
+ }
+ }
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This internal API is used to get the memory page based on register address.
+ */
+static int8_t get_mem_page(struct bme680_dev *dev)
+{
+ int8_t rslt;
+ uint8_t reg;
+
+ /* Check for null pointer in the device structure*/
+ rslt = null_ptr_check(dev);
+ if (rslt == BME680_OK) {
+ dev->com_rslt = dev->read(dev->dev_id, BME680_MEM_PAGE_ADDR | BME680_SPI_RD_MSK, ®, 1);
+ if (dev->com_rslt != 0)
+ rslt = BME680_E_COM_FAIL;
+ else
+ dev->mem_page = reg & BME680_MEM_PAGE_MSK;
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This internal API is used to validate the boundary
+ * conditions.
+ */
+static int8_t boundary_check(uint8_t *value, uint8_t min, uint8_t max, struct bme680_dev *dev)
+{
+ int8_t rslt = BME680_OK;
+
+ if (value != NULL) {
+ /* Check if value is below minimum value */
+ if (*value < min) {
+ /* Auto correct the invalid value to minimum value */
+ *value = min;
+ dev->info_msg |= BME680_I_MIN_CORRECTION;
+ }
+ /* Check if value is above maximum value */
+ if (*value > max) {
+ /* Auto correct the invalid value to maximum value */
+ *value = max;
+ dev->info_msg |= BME680_I_MAX_CORRECTION;
+ }
+ } else {
+ rslt = BME680_E_NULL_PTR;
+ }
+
+ return rslt;
+}
+
+/*!
+ * @brief This internal API is used to validate the device structure pointer for
+ * null conditions.
+ */
+static int8_t null_ptr_check(const struct bme680_dev *dev)
+{
+ int8_t rslt;
+
+ if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL)) {
+ /* Device structure pointer is not valid */
+ rslt = BME680_E_NULL_PTR;
+ } else {
+ /* Device structure is fine */
+ rslt = BME680_OK;
+ }
+
+ return rslt;
+}
diff --git a/lib/Bosch-BSEC/bme680.h b/lib/Bosch-BSEC/bme680.h
new file mode 100644
index 00000000..7c59be0f
--- /dev/null
+++ b/lib/Bosch-BSEC/bme680.h
@@ -0,0 +1,225 @@
+/**
+ * Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * Neither the name of the copyright holder nor the names of the
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+ * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
+ * OR CONTRIBUTORS BE LIABLE FOR ANY
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
+ * OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
+ *
+ * The information provided is believed to be accurate and reliable.
+ * The copyright holder assumes no responsibility
+ * for the consequences of use
+ * of such information nor for any infringement of patents or
+ * other rights of third parties which may result from its use.
+ * No license is granted by implication or otherwise under any patent or
+ * patent rights of the copyright holder.
+ *
+ * @file bme680.h
+ * @date 19 Jun 2018
+ * @version 3.5.9
+ * @brief
+ *
+ */
+/*! @file bme680.h
+ @brief Sensor driver for BME680 sensor */
+/*!
+ * @defgroup BME680 SENSOR API
+ * @{*/
+#ifndef BME680_H_
+#define BME680_H_
+
+/*! CPP guard */
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/* Header includes */
+#include "bme680_defs.h"
+
+/* function prototype declarations */
+/*!
+ * @brief This API is the entry point.
+ * It reads the chip-id and calibration data from the sensor.
+ *
+ * @param[in,out] dev : Structure instance of bme680_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bme680_init(struct bme680_dev *dev);
+
+/*!
+ * @brief This API writes the given data to the register address
+ * of the sensor.
+ *
+ * @param[in] reg_addr : Register address from where the data to be written.
+ * @param[in] reg_data : Pointer to data buffer which is to be written
+ * in the sensor.
+ * @param[in] len : No of bytes of data to write..
+ * @param[in] dev : Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bme680_set_regs(const uint8_t *reg_addr, const uint8_t *reg_data, uint8_t len, struct bme680_dev *dev);
+
+/*!
+ * @brief This API reads the data from the given register address of the sensor.
+ *
+ * @param[in] reg_addr : Register address from where the data to be read
+ * @param[out] reg_data : Pointer to data buffer to store the read data.
+ * @param[in] len : No of bytes of data to be read.
+ * @param[in] dev : Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bme680_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bme680_dev *dev);
+
+/*!
+ * @brief This API performs the soft reset of the sensor.
+ *
+ * @param[in] dev : Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
+ */
+int8_t bme680_soft_reset(struct bme680_dev *dev);
+
+/*!
+ * @brief This API is used to set the power mode of the sensor.
+ *
+ * @param[in] dev : Structure instance of bme680_dev
+ * @note : Pass the value to bme680_dev.power_mode structure variable.
+ *
+ * value | mode
+ * -------------|------------------
+ * 0x00 | BME680_SLEEP_MODE
+ * 0x01 | BME680_FORCED_MODE
+ *
+ * * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bme680_set_sensor_mode(struct bme680_dev *dev);
+
+/*!
+ * @brief This API is used to get the power mode of the sensor.
+ *
+ * @param[in] dev : Structure instance of bme680_dev
+ * @note : bme680_dev.power_mode structure variable hold the power mode.
+ *
+ * value | mode
+ * ---------|------------------
+ * 0x00 | BME680_SLEEP_MODE
+ * 0x01 | BME680_FORCED_MODE
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bme680_get_sensor_mode(struct bme680_dev *dev);
+
+/*!
+ * @brief This API is used to set the profile duration of the sensor.
+ *
+ * @param[in] dev : Structure instance of bme680_dev.
+ * @param[in] duration : Duration of the measurement in ms.
+ *
+ * @return Nothing
+ */
+void bme680_set_profile_dur(uint16_t duration, struct bme680_dev *dev);
+
+/*!
+ * @brief This API is used to get the profile duration of the sensor.
+ *
+ * @param[in] dev : Structure instance of bme680_dev.
+ * @param[in] duration : Duration of the measurement in ms.
+ *
+ * @return Nothing
+ */
+void bme680_get_profile_dur(uint16_t *duration, const struct bme680_dev *dev);
+
+/*!
+ * @brief This API reads the pressure, temperature and humidity and gas data
+ * from the sensor, compensates the data and store it in the bme680_data
+ * structure instance passed by the user.
+ *
+ * @param[out] data: Structure instance to hold the data.
+ * @param[in] dev : Structure instance of bme680_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bme680_get_sensor_data(struct bme680_field_data *data, struct bme680_dev *dev);
+
+/*!
+ * @brief This API is used to set the oversampling, filter and T,P,H, gas selection
+ * settings in the sensor.
+ *
+ * @param[in] dev : Structure instance of bme680_dev.
+ * @param[in] desired_settings : Variable used to select the settings which
+ * are to be set in the sensor.
+ *
+ * Macros | Functionality
+ *---------------------------------|----------------------------------------------
+ * BME680_OST_SEL | To set temperature oversampling.
+ * BME680_OSP_SEL | To set pressure oversampling.
+ * BME680_OSH_SEL | To set humidity oversampling.
+ * BME680_GAS_MEAS_SEL | To set gas measurement setting.
+ * BME680_FILTER_SEL | To set filter setting.
+ * BME680_HCNTRL_SEL | To set humidity control setting.
+ * BME680_RUN_GAS_SEL | To set run gas setting.
+ * BME680_NBCONV_SEL | To set NB conversion setting.
+ * BME680_GAS_SENSOR_SEL | To set all gas sensor related settings
+ *
+ * @note : Below are the macros to be used by the user for selecting the
+ * desired settings. User can do OR operation of these macros for configuring
+ * multiple settings.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
+ */
+int8_t bme680_set_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev);
+
+/*!
+ * @brief This API is used to get the oversampling, filter and T,P,H, gas selection
+ * settings in the sensor.
+ *
+ * @param[in] dev : Structure instance of bme680_dev.
+ * @param[in] desired_settings : Variable used to select the settings which
+ * are to be get from the sensor.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
+ */
+int8_t bme680_get_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev);
+#ifdef __cplusplus
+}
+#endif /* End of CPP guard */
+#endif /* BME680_H_ */
+/** @}*/
diff --git a/lib/Bosch-BSEC/bme680_defs.h b/lib/Bosch-BSEC/bme680_defs.h
new file mode 100644
index 00000000..495edfe0
--- /dev/null
+++ b/lib/Bosch-BSEC/bme680_defs.h
@@ -0,0 +1,545 @@
+/**
+ * Copyright (C) 2017 - 2018 Bosch Sensortec GmbH
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *
+ * Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * Neither the name of the copyright holder nor the names of the
+ * contributors may be used to endorse or promote products derived from
+ * this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+ * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
+ * OR CONTRIBUTORS BE LIABLE FOR ANY
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
+ * OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+ * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
+ *
+ * The information provided is believed to be accurate and reliable.
+ * The copyright holder assumes no responsibility
+ * for the consequences of use
+ * of such information nor for any infringement of patents or
+ * other rights of third parties which may result from its use.
+ * No license is granted by implication or otherwise under any patent or
+ * patent rights of the copyright holder.
+ *
+ * @file bme680_defs.h
+ * @date 19 Jun 2018
+ * @version 3.5.9
+ * @brief
+ *
+ */
+
+/*! @file bme680_defs.h
+ @brief Sensor driver for BME680 sensor */
+/*!
+ * @defgroup BME680 SENSOR API
+ * @brief
+ * @{*/
+#ifndef BME680_DEFS_H_
+#define BME680_DEFS_H_
+
+/********************************************************/
+/* header includes */
+#ifdef __KERNEL__
+#include
+#include
+#else
+#include
+#include
+#endif
+
+/******************************************************************************/
+/*! @name Common macros */
+/******************************************************************************/
+
+#if !defined(UINT8_C) && !defined(INT8_C)
+#define INT8_C(x) S8_C(x)
+#define UINT8_C(x) U8_C(x)
+#endif
+
+#if !defined(UINT16_C) && !defined(INT16_C)
+#define INT16_C(x) S16_C(x)
+#define UINT16_C(x) U16_C(x)
+#endif
+
+#if !defined(INT32_C) && !defined(UINT32_C)
+#define INT32_C(x) S32_C(x)
+#define UINT32_C(x) U32_C(x)
+#endif
+
+#if !defined(INT64_C) && !defined(UINT64_C)
+#define INT64_C(x) S64_C(x)
+#define UINT64_C(x) U64_C(x)
+#endif
+
+/**@}*/
+
+/**\name C standard macros */
+#ifndef NULL
+#ifdef __cplusplus
+#define NULL 0
+#else
+#define NULL ((void *) 0)
+#endif
+#endif
+
+/** BME680 configuration macros */
+/** Enable or un-comment the macro to provide floating point data output */
+#ifndef BME680_FLOAT_POINT_COMPENSATION
+/* #define BME680_FLOAT_POINT_COMPENSATION */
+#endif
+
+/** BME680 General config */
+#define BME680_POLL_PERIOD_MS UINT8_C(10)
+
+/** BME680 I2C addresses */
+#define BME680_I2C_ADDR_PRIMARY UINT8_C(0x76)
+#define BME680_I2C_ADDR_SECONDARY UINT8_C(0x77)
+
+/** BME680 unique chip identifier */
+#define BME680_CHIP_ID UINT8_C(0x61)
+
+/** BME680 coefficients related defines */
+#define BME680_COEFF_SIZE UINT8_C(41)
+#define BME680_COEFF_ADDR1_LEN UINT8_C(25)
+#define BME680_COEFF_ADDR2_LEN UINT8_C(16)
+
+/** BME680 field_x related defines */
+#define BME680_FIELD_LENGTH UINT8_C(15)
+#define BME680_FIELD_ADDR_OFFSET UINT8_C(17)
+
+/** Soft reset command */
+#define BME680_SOFT_RESET_CMD UINT8_C(0xb6)
+
+/** Error code definitions */
+#define BME680_OK INT8_C(0)
+/* Errors */
+#define BME680_E_NULL_PTR INT8_C(-1)
+#define BME680_E_COM_FAIL INT8_C(-2)
+#define BME680_E_DEV_NOT_FOUND INT8_C(-3)
+#define BME680_E_INVALID_LENGTH INT8_C(-4)
+
+/* Warnings */
+#define BME680_W_DEFINE_PWR_MODE INT8_C(1)
+#define BME680_W_NO_NEW_DATA INT8_C(2)
+
+/* Info's */
+#define BME680_I_MIN_CORRECTION UINT8_C(1)
+#define BME680_I_MAX_CORRECTION UINT8_C(2)
+
+/** Register map */
+/** Other coefficient's address */
+#define BME680_ADDR_RES_HEAT_VAL_ADDR UINT8_C(0x00)
+#define BME680_ADDR_RES_HEAT_RANGE_ADDR UINT8_C(0x02)
+#define BME680_ADDR_RANGE_SW_ERR_ADDR UINT8_C(0x04)
+#define BME680_ADDR_SENS_CONF_START UINT8_C(0x5A)
+#define BME680_ADDR_GAS_CONF_START UINT8_C(0x64)
+
+/** Field settings */
+#define BME680_FIELD0_ADDR UINT8_C(0x1d)
+
+/** Heater settings */
+#define BME680_RES_HEAT0_ADDR UINT8_C(0x5a)
+#define BME680_GAS_WAIT0_ADDR UINT8_C(0x64)
+
+/** Sensor configuration registers */
+#define BME680_CONF_HEAT_CTRL_ADDR UINT8_C(0x70)
+#define BME680_CONF_ODR_RUN_GAS_NBC_ADDR UINT8_C(0x71)
+#define BME680_CONF_OS_H_ADDR UINT8_C(0x72)
+#define BME680_MEM_PAGE_ADDR UINT8_C(0xf3)
+#define BME680_CONF_T_P_MODE_ADDR UINT8_C(0x74)
+#define BME680_CONF_ODR_FILT_ADDR UINT8_C(0x75)
+
+/** Coefficient's address */
+#define BME680_COEFF_ADDR1 UINT8_C(0x89)
+#define BME680_COEFF_ADDR2 UINT8_C(0xe1)
+
+/** Chip identifier */
+#define BME680_CHIP_ID_ADDR UINT8_C(0xd0)
+
+/** Soft reset register */
+#define BME680_SOFT_RESET_ADDR UINT8_C(0xe0)
+
+/** Heater control settings */
+#define BME680_ENABLE_HEATER UINT8_C(0x00)
+#define BME680_DISABLE_HEATER UINT8_C(0x08)
+
+/** Gas measurement settings */
+#define BME680_DISABLE_GAS_MEAS UINT8_C(0x00)
+#define BME680_ENABLE_GAS_MEAS UINT8_C(0x01)
+
+/** Over-sampling settings */
+#define BME680_OS_NONE UINT8_C(0)
+#define BME680_OS_1X UINT8_C(1)
+#define BME680_OS_2X UINT8_C(2)
+#define BME680_OS_4X UINT8_C(3)
+#define BME680_OS_8X UINT8_C(4)
+#define BME680_OS_16X UINT8_C(5)
+
+/** IIR filter settings */
+#define BME680_FILTER_SIZE_0 UINT8_C(0)
+#define BME680_FILTER_SIZE_1 UINT8_C(1)
+#define BME680_FILTER_SIZE_3 UINT8_C(2)
+#define BME680_FILTER_SIZE_7 UINT8_C(3)
+#define BME680_FILTER_SIZE_15 UINT8_C(4)
+#define BME680_FILTER_SIZE_31 UINT8_C(5)
+#define BME680_FILTER_SIZE_63 UINT8_C(6)
+#define BME680_FILTER_SIZE_127 UINT8_C(7)
+
+/** Power mode settings */
+#define BME680_SLEEP_MODE UINT8_C(0)
+#define BME680_FORCED_MODE UINT8_C(1)
+
+/** Delay related macro declaration */
+#define BME680_RESET_PERIOD UINT32_C(10)
+
+/** SPI memory page settings */
+#define BME680_MEM_PAGE0 UINT8_C(0x10)
+#define BME680_MEM_PAGE1 UINT8_C(0x00)
+
+/** Ambient humidity shift value for compensation */
+#define BME680_HUM_REG_SHIFT_VAL UINT8_C(4)
+
+/** Run gas enable and disable settings */
+#define BME680_RUN_GAS_DISABLE UINT8_C(0)
+#define BME680_RUN_GAS_ENABLE UINT8_C(1)
+
+/** Buffer length macro declaration */
+#define BME680_TMP_BUFFER_LENGTH UINT8_C(40)
+#define BME680_REG_BUFFER_LENGTH UINT8_C(6)
+#define BME680_FIELD_DATA_LENGTH UINT8_C(3)
+#define BME680_GAS_REG_BUF_LENGTH UINT8_C(20)
+
+/** Settings selector */
+#define BME680_OST_SEL UINT16_C(1)
+#define BME680_OSP_SEL UINT16_C(2)
+#define BME680_OSH_SEL UINT16_C(4)
+#define BME680_GAS_MEAS_SEL UINT16_C(8)
+#define BME680_FILTER_SEL UINT16_C(16)
+#define BME680_HCNTRL_SEL UINT16_C(32)
+#define BME680_RUN_GAS_SEL UINT16_C(64)
+#define BME680_NBCONV_SEL UINT16_C(128)
+#define BME680_GAS_SENSOR_SEL (BME680_GAS_MEAS_SEL | BME680_RUN_GAS_SEL | BME680_NBCONV_SEL)
+
+/** Number of conversion settings*/
+#define BME680_NBCONV_MIN UINT8_C(0)
+#define BME680_NBCONV_MAX UINT8_C(10)
+
+/** Mask definitions */
+#define BME680_GAS_MEAS_MSK UINT8_C(0x30)
+#define BME680_NBCONV_MSK UINT8_C(0X0F)
+#define BME680_FILTER_MSK UINT8_C(0X1C)
+#define BME680_OST_MSK UINT8_C(0XE0)
+#define BME680_OSP_MSK UINT8_C(0X1C)
+#define BME680_OSH_MSK UINT8_C(0X07)
+#define BME680_HCTRL_MSK UINT8_C(0x08)
+#define BME680_RUN_GAS_MSK UINT8_C(0x10)
+#define BME680_MODE_MSK UINT8_C(0x03)
+#define BME680_RHRANGE_MSK UINT8_C(0x30)
+#define BME680_RSERROR_MSK UINT8_C(0xf0)
+#define BME680_NEW_DATA_MSK UINT8_C(0x80)
+#define BME680_GAS_INDEX_MSK UINT8_C(0x0f)
+#define BME680_GAS_RANGE_MSK UINT8_C(0x0f)
+#define BME680_GASM_VALID_MSK UINT8_C(0x20)
+#define BME680_HEAT_STAB_MSK UINT8_C(0x10)
+#define BME680_MEM_PAGE_MSK UINT8_C(0x10)
+#define BME680_SPI_RD_MSK UINT8_C(0x80)
+#define BME680_SPI_WR_MSK UINT8_C(0x7f)
+#define BME680_BIT_H1_DATA_MSK UINT8_C(0x0F)
+
+/** Bit position definitions for sensor settings */
+#define BME680_GAS_MEAS_POS UINT8_C(4)
+#define BME680_FILTER_POS UINT8_C(2)
+#define BME680_OST_POS UINT8_C(5)
+#define BME680_OSP_POS UINT8_C(2)
+#define BME680_RUN_GAS_POS UINT8_C(4)
+
+/** Array Index to Field data mapping for Calibration Data*/
+#define BME680_T2_LSB_REG (1)
+#define BME680_T2_MSB_REG (2)
+#define BME680_T3_REG (3)
+#define BME680_P1_LSB_REG (5)
+#define BME680_P1_MSB_REG (6)
+#define BME680_P2_LSB_REG (7)
+#define BME680_P2_MSB_REG (8)
+#define BME680_P3_REG (9)
+#define BME680_P4_LSB_REG (11)
+#define BME680_P4_MSB_REG (12)
+#define BME680_P5_LSB_REG (13)
+#define BME680_P5_MSB_REG (14)
+#define BME680_P7_REG (15)
+#define BME680_P6_REG (16)
+#define BME680_P8_LSB_REG (19)
+#define BME680_P8_MSB_REG (20)
+#define BME680_P9_LSB_REG (21)
+#define BME680_P9_MSB_REG (22)
+#define BME680_P10_REG (23)
+#define BME680_H2_MSB_REG (25)
+#define BME680_H2_LSB_REG (26)
+#define BME680_H1_LSB_REG (26)
+#define BME680_H1_MSB_REG (27)
+#define BME680_H3_REG (28)
+#define BME680_H4_REG (29)
+#define BME680_H5_REG (30)
+#define BME680_H6_REG (31)
+#define BME680_H7_REG (32)
+#define BME680_T1_LSB_REG (33)
+#define BME680_T1_MSB_REG (34)
+#define BME680_GH2_LSB_REG (35)
+#define BME680_GH2_MSB_REG (36)
+#define BME680_GH1_REG (37)
+#define BME680_GH3_REG (38)
+
+/** BME680 register buffer index settings*/
+#define BME680_REG_FILTER_INDEX UINT8_C(5)
+#define BME680_REG_TEMP_INDEX UINT8_C(4)
+#define BME680_REG_PRES_INDEX UINT8_C(4)
+#define BME680_REG_HUM_INDEX UINT8_C(2)
+#define BME680_REG_NBCONV_INDEX UINT8_C(1)
+#define BME680_REG_RUN_GAS_INDEX UINT8_C(1)
+#define BME680_REG_HCTRL_INDEX UINT8_C(0)
+
+/** BME680 pressure calculation macros */
+/*! This max value is used to provide precedence to multiplication or division
+ * in pressure compensation equation to achieve least loss of precision and
+ * avoiding overflows.
+ * i.e Comparing value, BME680_MAX_OVERFLOW_VAL = INT32_C(1 << 30)
+ */
+#define BME680_MAX_OVERFLOW_VAL INT32_C(0x40000000)
+
+/** Macro to combine two 8 bit data's to form a 16 bit data */
+#define BME680_CONCAT_BYTES(msb, lsb) (((uint16_t)msb << 8) | (uint16_t)lsb)
+
+/** Macro to SET and GET BITS of a register */
+#define BME680_SET_BITS(reg_data, bitname, data) \
+ ((reg_data & ~(bitname##_MSK)) | \
+ ((data << bitname##_POS) & bitname##_MSK))
+#define BME680_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> \
+ (bitname##_POS))
+
+/** Macro variant to handle the bitname position if it is zero */
+#define BME680_SET_BITS_POS_0(reg_data, bitname, data) \
+ ((reg_data & ~(bitname##_MSK)) | \
+ (data & bitname##_MSK))
+#define BME680_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK))
+
+/** Type definitions */
+/*!
+ * Generic communication function pointer
+ * @param[in] dev_id: Place holder to store the id of the device structure
+ * Can be used to store the index of the Chip select or
+ * I2C address of the device.
+ * @param[in] reg_addr: Used to select the register the where data needs to
+ * be read from or written to.
+ * @param[in/out] reg_data: Data array to read/write
+ * @param[in] len: Length of the data array
+ */
+typedef int8_t (*bme680_com_fptr_t)(uint8_t dev_id, uint8_t reg_addr, uint8_t *data, uint16_t len);
+
+/*!
+ * Delay function pointer
+ * @param[in] period: Time period in milliseconds
+ */
+typedef void (*bme680_delay_fptr_t)(uint32_t period);
+
+/*!
+ * @brief Interface selection Enumerations
+ */
+enum bme680_intf {
+ /*! SPI interface */
+ BME680_SPI_INTF,
+ /*! I2C interface */
+ BME680_I2C_INTF
+};
+
+/* structure definitions */
+/*!
+ * @brief Sensor field data structure
+ */
+struct bme680_field_data {
+ /*! Contains new_data, gasm_valid & heat_stab */
+ uint8_t status;
+ /*! The index of the heater profile used */
+ uint8_t gas_index;
+ /*! Measurement index to track order */
+ uint8_t meas_index;
+
+#ifndef BME680_FLOAT_POINT_COMPENSATION
+ /*! Temperature in degree celsius x100 */
+ int16_t temperature;
+ /*! Pressure in Pascal */
+ uint32_t pressure;
+ /*! Humidity in % relative humidity x1000 */
+ uint32_t humidity;
+ /*! Gas resistance in Ohms */
+ uint32_t gas_resistance;
+#else
+ /*! Temperature in degree celsius */
+ float temperature;
+ /*! Pressure in Pascal */
+ float pressure;
+ /*! Humidity in % relative humidity x1000 */
+ float humidity;
+ /*! Gas resistance in Ohms */
+ float gas_resistance;
+
+#endif
+
+};
+
+/*!
+ * @brief Structure to hold the Calibration data
+ */
+struct bme680_calib_data {
+ /*! Variable to store calibrated humidity data */
+ uint16_t par_h1;
+ /*! Variable to store calibrated humidity data */
+ uint16_t par_h2;
+ /*! Variable to store calibrated humidity data */
+ int8_t par_h3;
+ /*! Variable to store calibrated humidity data */
+ int8_t par_h4;
+ /*! Variable to store calibrated humidity data */
+ int8_t par_h5;
+ /*! Variable to store calibrated humidity data */
+ uint8_t par_h6;
+ /*! Variable to store calibrated humidity data */
+ int8_t par_h7;
+ /*! Variable to store calibrated gas data */
+ int8_t par_gh1;
+ /*! Variable to store calibrated gas data */
+ int16_t par_gh2;
+ /*! Variable to store calibrated gas data */
+ int8_t par_gh3;
+ /*! Variable to store calibrated temperature data */
+ uint16_t par_t1;
+ /*! Variable to store calibrated temperature data */
+ int16_t par_t2;
+ /*! Variable to store calibrated temperature data */
+ int8_t par_t3;
+ /*! Variable to store calibrated pressure data */
+ uint16_t par_p1;
+ /*! Variable to store calibrated pressure data */
+ int16_t par_p2;
+ /*! Variable to store calibrated pressure data */
+ int8_t par_p3;
+ /*! Variable to store calibrated pressure data */
+ int16_t par_p4;
+ /*! Variable to store calibrated pressure data */
+ int16_t par_p5;
+ /*! Variable to store calibrated pressure data */
+ int8_t par_p6;
+ /*! Variable to store calibrated pressure data */
+ int8_t par_p7;
+ /*! Variable to store calibrated pressure data */
+ int16_t par_p8;
+ /*! Variable to store calibrated pressure data */
+ int16_t par_p9;
+ /*! Variable to store calibrated pressure data */
+ uint8_t par_p10;
+
+#ifndef BME680_FLOAT_POINT_COMPENSATION
+ /*! Variable to store t_fine size */
+ int32_t t_fine;
+#else
+ /*! Variable to store t_fine size */
+ float t_fine;
+#endif
+ /*! Variable to store heater resistance range */
+ uint8_t res_heat_range;
+ /*! Variable to store heater resistance value */
+ int8_t res_heat_val;
+ /*! Variable to store error range */
+ int8_t range_sw_err;
+};
+
+/*!
+ * @brief BME680 sensor settings structure which comprises of ODR,
+ * over-sampling and filter settings.
+ */
+struct bme680_tph_sett {
+ /*! Humidity oversampling */
+ uint8_t os_hum;
+ /*! Temperature oversampling */
+ uint8_t os_temp;
+ /*! Pressure oversampling */
+ uint8_t os_pres;
+ /*! Filter coefficient */
+ uint8_t filter;
+};
+
+/*!
+ * @brief BME680 gas sensor which comprises of gas settings
+ * and status parameters
+ */
+struct bme680_gas_sett {
+ /*! Variable to store nb conversion */
+ uint8_t nb_conv;
+ /*! Variable to store heater control */
+ uint8_t heatr_ctrl;
+ /*! Run gas enable value */
+ uint8_t run_gas;
+ /*! Heater temperature value */
+ uint16_t heatr_temp;
+ /*! Duration profile value */
+ uint16_t heatr_dur;
+};
+
+/*!
+ * @brief BME680 device structure
+ */
+struct bme680_dev {
+ /*! Chip Id */
+ uint8_t chip_id;
+ /*! Device Id */
+ uint8_t dev_id;
+ /*! SPI/I2C interface */
+ enum bme680_intf intf;
+ /*! Memory page used */
+ uint8_t mem_page;
+ /*! Ambient temperature in Degree C */
+ int8_t amb_temp;
+ /*! Sensor calibration data */
+ struct bme680_calib_data calib;
+ /*! Sensor settings */
+ struct bme680_tph_sett tph_sett;
+ /*! Gas Sensor settings */
+ struct bme680_gas_sett gas_sett;
+ /*! Sensor power modes */
+ uint8_t power_mode;
+ /*! New sensor fields */
+ uint8_t new_fields;
+ /*! Store the info messages */
+ uint8_t info_msg;
+ /*! Bus read function pointer */
+ bme680_com_fptr_t read;
+ /*! Bus write function pointer */
+ bme680_com_fptr_t write;
+ /*! delay function pointer */
+ bme680_delay_fptr_t delay_ms;
+ /*! Communication function result */
+ int8_t com_rslt;
+};
+
+
+
+#endif /* BME680_DEFS_H_ */
+/** @}*/
+/** @}*/
diff --git a/lib/Bosch-BSEC/bsec_datatypes.h b/lib/Bosch-BSEC/bsec_datatypes.h
new file mode 100644
index 00000000..6b4f43df
--- /dev/null
+++ b/lib/Bosch-BSEC/bsec_datatypes.h
@@ -0,0 +1,488 @@
+/*
+ * Copyright (C) 2015, 2016, 2017 Robert Bosch. All Rights Reserved.
+ *
+ * Disclaimer
+ *
+ * Common:
+ * Bosch Sensortec products are developed for the consumer goods industry. They may only be used
+ * within the parameters of the respective valid product data sheet. Bosch Sensortec products are
+ * provided with the express understanding that there is no warranty of fitness for a particular purpose.
+ * They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
+ * that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
+ * Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
+ * The resale and/or use of products are at the purchasers own risk and his own responsibility. The
+ * examination of fitness for the intended use is the sole responsibility of the Purchaser.
+ *
+ * The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
+ * incidental, or consequential damages, arising from any product use not covered by the parameters of
+ * the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
+ * Sensortec for all costs in connection with such claims.
+ *
+ * The purchaser must monitor the market for the purchased products, particularly with regard to
+ * product safety and inform Bosch Sensortec without delay of all security relevant incidents.
+ *
+ * Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
+ * technical specifications of the product series. They are therefore not intended or fit for resale to third
+ * parties or for use in end products. Their sole purpose is internal client testing. The testing of an
+ * engineering sample may in no way replace the testing of a product series. Bosch Sensortec
+ * assumes no liability for the use of engineering samples. By accepting the engineering samples, the
+ * Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
+ * samples.
+ *
+ * Special:
+ * This software module (hereinafter called "Software") and any information on application-sheets
+ * (hereinafter called "Information") is provided free of charge for the sole purpose to support your
+ * application work. The Software and Information is subject to the following terms and conditions:
+ *
+ * The Software is specifically designed for the exclusive use for Bosch Sensortec products by
+ * personnel who have special experience and training. Do not use this Software if you do not have the
+ * proper experience or training.
+ *
+ * This Software package is provided `` as is `` and without any expressed or implied warranties,
+ * including without limitation, the implied warranties of merchantability and fitness for a particular
+ * purpose.
+ *
+ * Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
+ * of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
+ * representatives and agents shall not be liable for any direct or indirect damages or injury, except as
+ * otherwise stipulated in mandatory applicable law.
+ *
+ * The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
+ * responsibility for the consequences of use of such Information nor for any infringement of patents or
+ * other rights of third parties which may result from its use. No license is granted by implication or
+ * otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
+ * subject to change without notice.
+ *
+ * It is not allowed to deliver the source code of the Software to any third party without permission of
+ * Bosch Sensortec.
+ *
+ */
+
+ /**
+ * @file bsec_datatypes.h
+ *
+ * @brief
+ * Contains the data types used by BSEC
+ *
+ */
+
+#ifndef __BSEC_DATATYPES_H__
+#define __BSEC_DATATYPES_H__
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/*!
+ * @addtogroup bsec_interface BSEC C Interface
+ * @{*/
+
+#ifdef __KERNEL__
+#include
+#endif
+#include
+#include
+
+#define BSEC_MAX_WORKBUFFER_SIZE (2048) /*!< Maximum size (in bytes) of the work buffer */
+#define BSEC_MAX_PHYSICAL_SENSOR (8) /*!< Number of physical sensors that need allocated space before calling bsec_update_subscription() */
+#define BSEC_MAX_PROPERTY_BLOB_SIZE (454) /*!< Maximum size (in bytes) of the data blobs returned by bsec_get_configuration() */
+#define BSEC_MAX_STATE_BLOB_SIZE (134) /*!< Maximum size (in bytes) of the data blobs returned by bsec_get_state()*/
+#define BSEC_SAMPLE_RATE_DISABLED (65535.0f) /*!< Sample rate of a disabled sensor */
+#define BSEC_SAMPLE_RATE_ULP (0.0033333f) /*!< Sample rate in case of Ultra Low Power Mode */
+#define BSEC_SAMPLE_RATE_LP (0.33333f) /*!< Sample rate in case of Low Power Mode */
+#define BSEC_SAMPLE_RATE_ULP_MEASUREMENT_ON_DEMAND (0.0f) /*!< Input value used to trigger an extra measurment (ULP plus) */
+
+#define BSEC_PROCESS_PRESSURE (1 << (BSEC_INPUT_PRESSURE-1)) /*!< process_data bitfield constant for pressure @sa bsec_bme_settings_t */
+#define BSEC_PROCESS_TEMPERATURE (1 << (BSEC_INPUT_TEMPERATURE-1)) /*!< process_data bitfield constant for temperature @sa bsec_bme_settings_t */
+#define BSEC_PROCESS_HUMIDITY (1 << (BSEC_INPUT_HUMIDITY-1)) /*!< process_data bitfield constant for humidity @sa bsec_bme_settings_t */
+#define BSEC_PROCESS_GAS (1 << (BSEC_INPUT_GASRESISTOR-1)) /*!< process_data bitfield constant for gas sensor @sa bsec_bme_settings_t */
+#define BSEC_NUMBER_OUTPUTS (14) /*!< Number of outputs, depending on solution */
+#define BSEC_OUTPUT_INCLUDED (1210863) /*!< bitfield that indicates which outputs are included in the solution */
+
+/*!
+ * @brief Enumeration for input (physical) sensors.
+ *
+ * Used to populate bsec_input_t::sensor_id. It is also used in bsec_sensor_configuration_t::sensor_id structs
+ * returned in the parameter required_sensor_settings of bsec_update_subscription().
+ *
+ * @sa bsec_sensor_configuration_t @sa bsec_input_t
+ */
+typedef enum
+{
+ /**
+ * @brief Pressure sensor output of BMExxx [Pa]
+ */
+ BSEC_INPUT_PRESSURE = 1,
+
+ /**
+ * @brief Humidity sensor output of BMExxx [%]
+ *
+ * @note Relative humidity strongly depends on the temperature (it is measured at). It may require a conversion to
+ * the temperature outside of the device.
+ *
+ * @sa bsec_virtual_sensor_t
+ */
+ BSEC_INPUT_HUMIDITY = 2,
+
+ /**
+ * @brief Temperature sensor output of BMExxx [degrees Celsius]
+ *
+ * @note The BME680 is factory trimmed, thus the temperature sensor of the BME680 is very accurate.
+ * The temperature value is a very local measurement value and can be influenced by external heat sources.
+ *
+ * @sa bsec_virtual_sensor_t
+ */
+ BSEC_INPUT_TEMPERATURE = 3,
+
+ /**
+ * @brief Gas sensor resistance output of BMExxx [Ohm]
+ *
+ * The resistance value changes due to varying VOC concentrations (the higher the concentration of reducing VOCs,
+ * the lower the resistance and vice versa).
+ */
+ BSEC_INPUT_GASRESISTOR = 4, /*!< */
+
+ /**
+ * @brief Additional input for device heat compensation
+ *
+ * IAQ solution: The value is subtracted from ::BSEC_INPUT_TEMPERATURE to compute
+ * ::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE.
+ *
+ * ALL solution: Generic heat source 1
+ *
+ * @sa bsec_virtual_sensor_t
+ */
+ BSEC_INPUT_HEATSOURCE = 14,
+
+ /**
+ * @brief Additional input for device heat compensation 8
+ *
+ * Generic heat source 8
+ */
+
+
+ /**
+ * @brief Additional input that disables baseline tracker
+ *
+ * 0 - Normal
+ * 1 - Event 1
+ * 2 - Event 2
+ */
+ BSEC_INPUT_DISABLE_BASELINE_TRACKER = 23,
+
+} bsec_physical_sensor_t;
+
+/*!
+ * @brief Enumeration for output (virtual) sensors
+ *
+ * Used to populate bsec_output_t::sensor_id. It is also used in bsec_sensor_configuration_t::sensor_id structs
+ * passed in the parameter requested_virtual_sensors of bsec_update_subscription().
+ *
+ * @sa bsec_sensor_configuration_t @sa bsec_output_t
+ */
+typedef enum
+{
+ /**
+ * @brief Indoor-air-quality estimate [0-500]
+ *
+ * Indoor-air-quality (IAQ) gives an indication of the relative change in ambient TVOCs detected by BME680.
+ *
+ * @note The IAQ scale ranges from 0 (clean air) to 500 (heavily polluted air). During operation, algorithms
+ * automatically calibrate and adapt themselves to the typical environments where the sensor is operated
+ * (e.g., home, workplace, inside a car, etc.).This automatic background calibration ensures that users experience
+ * consistent IAQ performance. The calibration process considers the recent measurement history (typ. up to four
+ * days) to ensure that IAQ=25 corresponds to typical good air and IAQ=250 indicates typical polluted air.
+ */
+ BSEC_OUTPUT_IAQ = 1,
+ BSEC_OUTPUT_STATIC_IAQ = 2, /*!< Unscaled indoor-air-quality estimate */
+ BSEC_OUTPUT_CO2_EQUIVALENT = 3, /*!< co2 equivalent estimate [ppm] */
+ BSEC_OUTPUT_BREATH_VOC_EQUIVALENT = 4, /*!< breath VOC concentration estimate [ppm] */
+
+ /**
+ * @brief Temperature sensor signal [degrees Celsius]
+ *
+ * Temperature directly measured by BME680 in degree Celsius.
+ *
+ * @note This value is cross-influenced by the sensor heating and device specific heating.
+ */
+ BSEC_OUTPUT_RAW_TEMPERATURE = 6,
+
+ /**
+ * @brief Pressure sensor signal [Pa]
+ *
+ * Pressure directly measured by the BME680 in Pa.
+ */
+ BSEC_OUTPUT_RAW_PRESSURE = 7,
+
+ /**
+ * @brief Relative humidity sensor signal [%]
+ *
+ * Relative humidity directly measured by the BME680 in %.
+ *
+ * @note This value is cross-influenced by the sensor heating and device specific heating.
+ */
+ BSEC_OUTPUT_RAW_HUMIDITY = 8,
+
+ /**
+ * @brief Gas sensor signal [Ohm]
+ *
+ * Gas resistance measured directly by the BME680 in Ohm.The resistance value changes due to varying VOC
+ * concentrations (the higher the concentration of reducing VOCs, the lower the resistance and vice versa).
+ */
+ BSEC_OUTPUT_RAW_GAS = 9,
+
+ /**
+ * @brief Gas sensor stabilization status [boolean]
+ *
+ * Indicates initial stabilization status of the gas sensor element: stabilization is ongoing (0) or stabilization
+ * is finished (1).
+ */
+ BSEC_OUTPUT_STABILIZATION_STATUS = 12,
+
+ /**
+ * @brief Gas sensor run-in status [boolean]
+ *
+ * Indicates power-on stabilization status of the gas sensor element: stabilization is ongoing (0) or stabilization
+ * is finished (1).
+ */
+ BSEC_OUTPUT_RUN_IN_STATUS = 13,
+
+ /**
+ * @brief Sensor heat compensated temperature [degrees Celsius]
+ *
+ * Temperature measured by BME680 which is compensated for the influence of sensor (heater) in degree Celsius.
+ * The self heating introduced by the heater is depending on the sensor operation mode and the sensor supply voltage.
+ *
+ *
+ * @note IAQ solution: In addition, the temperature output can be compensated by an user defined value
+ * (::BSEC_INPUT_HEATSOURCE in degrees Celsius), which represents the device specific self-heating.
+ *
+ * Thus, the value is calculated as follows:
+ * * IAQ solution: ```BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE = ::BSEC_INPUT_TEMPERATURE - function(sensor operation mode, sensor supply voltage) - ::BSEC_INPUT_HEATSOURCE```
+ * * other solutions: ```::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE = ::BSEC_INPUT_TEMPERATURE - function(sensor operation mode, sensor supply voltage)```
+ *
+ * The self-heating in operation mode BSEC_SAMPLE_RATE_ULP is negligible.
+ * The self-heating in operation mode BSEC_SAMPLE_RATE_LP is supported for 1.8V by default (no config file required). If the BME680 sensor supply voltage is 3.3V, the IoT_LP_3_3V.config shall be used.
+ */
+ BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE = 14,
+
+ /**
+ * @brief Sensor heat compensated humidity [%]
+ *
+ * Relative measured by BME680 which is compensated for the influence of sensor (heater) in %.
+ *
+ * It converts the ::BSEC_INPUT_HUMIDITY from temperature ::BSEC_INPUT_TEMPERATURE to temperature
+ * ::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE.
+ *
+ * @note IAQ solution: If ::BSEC_INPUT_HEATSOURCE is used for device specific temperature compensation, it will be
+ * effective for ::BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY too.
+ */
+ BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY = 15,
+
+ BSEC_OUTPUT_COMPENSATED_GAS = 18, /*!< Reserved internal debug output */
+ BSEC_OUTPUT_GAS_PERCENTAGE = 21 /*!< percentage of min and max filtered gas value [%] */
+} bsec_virtual_sensor_t;
+
+/*!
+ * @brief Enumeration for function return codes
+ */
+typedef enum
+{
+ BSEC_OK = 0, /*!< Function execution successful */
+ BSEC_E_DOSTEPS_INVALIDINPUT = -1, /*!< Input (physical) sensor id passed to bsec_do_steps() is not in the valid range or not valid for requested virtual sensor */
+ BSEC_E_DOSTEPS_VALUELIMITS = -2, /*!< Value of input (physical) sensor signal passed to bsec_do_steps() is not in the valid range */
+ BSEC_E_DOSTEPS_DUPLICATEINPUT = -6, /*!< Duplicate input (physical) sensor ids passed as input to bsec_do_steps() */
+ BSEC_I_DOSTEPS_NOOUTPUTSRETURNABLE = 2, /*!< No memory allocated to hold return values from bsec_do_steps(), i.e., n_outputs == 0 */
+ BSEC_W_DOSTEPS_EXCESSOUTPUTS = 3, /*!< Not enough memory allocated to hold return values from bsec_do_steps(), i.e., n_outputs < maximum number of requested output (virtual) sensors */
+ BSEC_W_DOSTEPS_TSINTRADIFFOUTOFRANGE = 4, /*!< Duplicate timestamps passed to bsec_do_steps() */
+ BSEC_E_SU_WRONGDATARATE = -10, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() is zero */
+ BSEC_E_SU_SAMPLERATELIMITS = -12, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() does not match with the sampling rate allowed for that sensor */
+ BSEC_E_SU_DUPLICATEGATE = -13, /*!< Duplicate output (virtual) sensor ids requested through bsec_update_subscription() */
+ BSEC_E_SU_INVALIDSAMPLERATE = -14, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() does not fall within the global minimum and maximum sampling rates */
+ BSEC_E_SU_GATECOUNTEXCEEDSARRAY = -15, /*!< Not enough memory allocated to hold returned input (physical) sensor data from bsec_update_subscription(), i.e., n_required_sensor_settings < #BSEC_MAX_PHYSICAL_SENSOR */
+ BSEC_E_SU_SAMPLINTVLINTEGERMULT = -16, /*!< The sample_rate of the requested output (virtual) sensor passed to bsec_update_subscription() is not correct */
+ BSEC_E_SU_MULTGASSAMPLINTVL = -17, /*!< The sample_rate of the requested output (virtual), which requires the gas sensor, is not equal to the sample_rate that the gas sensor is being operated */
+ BSEC_E_SU_HIGHHEATERONDURATION = -18, /*!< The duration of one measurement is longer than the requested sampling interval */
+ BSEC_W_SU_UNKNOWNOUTPUTGATE = 10, /*!< Output (virtual) sensor id passed to bsec_update_subscription() is not in the valid range; e.g., n_requested_virtual_sensors > actual number of output (virtual) sensors requested */
+ BSEC_W_SU_MODINNOULP = 11, /*!< ULP plus can not be requested in non-ulp mode */ /*MOD_ONLY*/
+ BSEC_I_SU_SUBSCRIBEDOUTPUTGATES = 12, /*!< No output (virtual) sensor data were requested via bsec_update_subscription() */
+ BSEC_E_PARSE_SECTIONEXCEEDSWORKBUFFER = -32, /*!< n_work_buffer_size passed to bsec_set_[configuration/state]() not sufficient */
+ BSEC_E_CONFIG_FAIL = -33, /*!< Configuration failed */
+ BSEC_E_CONFIG_VERSIONMISMATCH = -34, /*!< Version encoded in serialized_[settings/state] passed to bsec_set_[configuration/state]() does not match with current version */
+ BSEC_E_CONFIG_FEATUREMISMATCH = -35, /*!< Enabled features encoded in serialized_[settings/state] passed to bsec_set_[configuration/state]() does not match with current library implementation */
+ BSEC_E_CONFIG_CRCMISMATCH = -36, /*!< serialized_[settings/state] passed to bsec_set_[configuration/state]() is corrupted */
+ BSEC_E_CONFIG_EMPTY = -37, /*!< n_serialized_[settings/state] passed to bsec_set_[configuration/state]() is to short to be valid */
+ BSEC_E_CONFIG_INSUFFICIENTWORKBUFFER = -38, /*!< Provided work_buffer is not large enough to hold the desired string */
+ BSEC_E_CONFIG_INVALIDSTRINGSIZE = -40, /*!< String size encoded in configuration/state strings passed to bsec_set_[configuration/state]() does not match with the actual string size n_serialized_[settings/state] passed to these functions */
+ BSEC_E_CONFIG_INSUFFICIENTBUFFER = -41, /*!< String buffer insufficient to hold serialized data from BSEC library */
+ BSEC_E_SET_INVALIDCHANNELIDENTIFIER = -100, /*!< Internal error code, size of work buffer in setConfig must be set to BSEC_MAX_WORKBUFFER_SIZE */
+ BSEC_E_SET_INVALIDLENGTH = -104, /*!< Internal error code */
+ BSEC_W_SC_CALL_TIMING_VIOLATION = 100, /*!< Difference between actual and defined sampling intervals of bsec_sensor_control() greater than allowed */
+ BSEC_W_SC_MODEXCEEDULPTIMELIMIT = 101, /*!< ULP plus is not allowed because an ULP measurement just took or will take place */ /*MOD_ONLY*/
+ BSEC_W_SC_MODINSUFFICIENTWAITTIME = 102 /*!< ULP plus is not allowed because not sufficient time passed since last ULP plus */ /*MOD_ONLY*/
+} bsec_library_return_t;
+
+/*!
+ * @brief Structure containing the version information
+ *
+ * Please note that configuration and state strings are coded to a specific version and will not be accepted by other
+ * versions of BSEC.
+ *
+ */
+typedef struct
+{
+ uint8_t major; /**< @brief Major version */
+ uint8_t minor; /**< @brief Minor version */
+ uint8_t major_bugfix; /**< @brief Major bug fix version */
+ uint8_t minor_bugfix; /**< @brief Minor bug fix version */
+} bsec_version_t;
+
+/*!
+ * @brief Structure describing an input sample to the library
+ *
+ * Each input sample is provided to BSEC as an element in a struct array of this type. Timestamps must be provided
+ * in nanosecond resolution. Moreover, duplicate timestamps for subsequent samples are not allowed and will results in
+ * an error code being returned from bsec_do_steps().
+ *
+ * The meaning unit of the signal field are determined by the bsec_input_t::sensor_id field content. Possible
+ * bsec_input_t::sensor_id values and and their meaning are described in ::bsec_physical_sensor_t.
+ *
+ * @sa bsec_physical_sensor_t
+ *
+ */
+typedef struct
+{
+ /**
+ * @brief Time stamp in nanosecond resolution [ns]
+ *
+ * Timestamps must be provided as non-repeating and increasing values. They can have their 0-points at system start or
+ * at a defined wall-clock time (e.g., 01-Jan-1970 00:00:00)
+ */
+ int64_t time_stamp;
+ float signal; /*!< @brief Signal sample in the unit defined for the respective sensor_id @sa bsec_physical_sensor_t */
+ uint8_t signal_dimensions; /*!< @brief Signal dimensions (reserved for future use, shall be set to 1) */
+ uint8_t sensor_id; /*!< @brief Identifier of physical sensor @sa bsec_physical_sensor_t */
+} bsec_input_t;
+
+/*!
+ * @brief Structure describing an output sample of the library
+ *
+ * Each output sample is returned from BSEC by populating the element of a struct array of this type. The contents of
+ * the signal field is defined by the supplied bsec_output_t::sensor_id. Possible output
+ * bsec_output_t::sensor_id values are defined in ::bsec_virtual_sensor_t.
+ *
+ * @sa bsec_virtual_sensor_t
+ */
+typedef struct
+{
+ int64_t time_stamp; /*!< @brief Time stamp in nanosecond resolution as provided as input [ns] */
+ float signal; /*!< @brief Signal sample in the unit defined for the respective bsec_output_t::sensor_id @sa bsec_virtual_sensor_t */
+ uint8_t signal_dimensions; /*!< @brief Signal dimensions (reserved for future use, shall be set to 1) */
+ uint8_t sensor_id; /*!< @brief Identifier of virtual sensor @sa bsec_virtual_sensor_t */
+
+ /**
+ * @brief Accuracy status 0-3
+ *
+ * Some virtual sensors provide a value in the accuracy field. If this is the case, the meaning of the field is as
+ * follows:
+ *
+ * | Name | Value | Accuracy description |
+ * |----------------------------|-------|-------------------------------------------------------------|
+ * | UNRELIABLE | 0 | Sensor data is unreliable, the sensor must be calibrated |
+ * | LOW_ACCURACY | 1 | Low accuracy, sensor should be calibrated |
+ * | MEDIUM_ACCURACY | 2 | Medium accuracy, sensor calibration may improve performance |
+ * | HIGH_ACCURACY | 3 | High accuracy |
+ *
+ * For example:
+ *
+ * - Ambient temperature accuracy is derived from change in the temperature in 1 minute.
+ *
+ * | Virtual sensor | Value | Accuracy description |
+ * |--------------------- |-------|------------------------------------------------------------------------------|
+ * | Ambient temperature | 0 | The difference in ambient temperature is greater than 4 degree in one minute |
+ * | | 1 | The difference in ambient temperature is less than 4 degree in one minute |
+ * | | 2 | The difference in ambient temperature is less than 3 degree in one minute |
+ * | | 3 | The difference in ambient temperature is less than 2 degree in one minute |
+ *
+ * - IAQ accuracy indicator will notify the user when she/he should initiate a calibration process. Calibration is
+ * performed automatically in the background if the sensor is exposed to clean and polluted air for approximately
+ * 30 minutes each.
+ *
+ * | Virtual sensor | Value | Accuracy description |
+ * |----------------------------|-------|-----------------------------------------------------------------|
+ * | IAQ | 0 | The sensor is not yet stabilized or in a run-in status |
+ * | | 1 | Calibration required |
+ * | | 2 | Calibration on-going |
+ * | | 3 | Calibration is done, now IAQ estimate achieves best performance |
+ */
+ uint8_t accuracy;
+} bsec_output_t;
+
+/*!
+ * @brief Structure describing sample rate of physical/virtual sensors
+ *
+ * This structure is used together with bsec_update_subscription() to enable BSEC outputs and to retrieve information
+ * about the sample rates used for BSEC inputs.
+ */
+typedef struct
+{
+ /**
+ * @brief Sample rate of the virtual or physical sensor in Hertz [Hz]
+ *
+ * Only supported sample rates are allowed.
+ */
+ float sample_rate;
+
+ /**
+ * @brief Identifier of the virtual or physical sensor
+ *
+ * The meaning of this field changes depending on whether the structs are as the requested_virtual_sensors argument
+ * to bsec_update_subscription() or as the required_sensor_settings argument.
+ *
+ * | bsec_update_subscription() argument | sensor_id field interpretation |
+ * |-------------------------------------|--------------------------------|
+ * | requested_virtual_sensors | ::bsec_virtual_sensor_t |
+ * | required_sensor_settings | ::bsec_physical_sensor_t |
+ *
+ * @sa bsec_physical_sensor_t
+ * @sa bsec_virtual_sensor_t
+ */
+ uint8_t sensor_id;
+} bsec_sensor_configuration_t;
+
+/*!
+ * @brief Structure returned by bsec_sensor_control() to configure BMExxx sensor
+ *
+ * This structure contains settings that must be used to configure the BMExxx to perform a forced-mode measurement.
+ * A measurement should only be executed if bsec_bme_settings_t::trigger_measurement is 1. If so, the oversampling
+ * settings for temperature, humidity, and pressure should be set to the provided settings provided in
+ * bsec_bme_settings_t::temperature_oversampling, bsec_bme_settings_t::humidity_oversampling, and
+ * bsec_bme_settings_t::pressure_oversampling, respectively.
+ *
+ * In case of bsec_bme_settings_t::run_gas = 1, the gas sensor must be enabled with the provided
+ * bsec_bme_settings_t::heater_temperature and bsec_bme_settings_t::heating_duration settings.
+ */
+typedef struct
+{
+ int64_t next_call; /*!< @brief Time stamp of the next call of the sensor_control*/
+ uint32_t process_data; /*!< @brief Bit field describing which data is to be passed to bsec_do_steps() @sa BSEC_PROCESS_* */
+ uint16_t heater_temperature; /*!< @brief Heating temperature [degrees Celsius] */
+ uint16_t heating_duration; /*!< @brief Heating duration [ms] */
+ uint8_t run_gas; /*!< @brief Enable gas measurements [0/1] */
+ uint8_t pressure_oversampling; /*!< @brief Pressure oversampling settings [0-5] */
+ uint8_t temperature_oversampling; /*!< @brief Temperature oversampling settings [0-5] */
+ uint8_t humidity_oversampling; /*!< @brief Humidity oversampling settings [0-5] */
+ uint8_t trigger_measurement; /*!< @brief Trigger a forced measurement with these settings now [0/1] */
+} bsec_bme_settings_t;
+
+/* internal defines and backward compatibility */
+#define BSEC_STRUCT_NAME Bsec /*!< Internal struct name */
+
+/*@}*/
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/lib/Bosch-BSEC/bsec_integration.c b/lib/Bosch-BSEC/bsec_integration.c
new file mode 100644
index 00000000..0dc5dc2d
--- /dev/null
+++ b/lib/Bosch-BSEC/bsec_integration.c
@@ -0,0 +1,559 @@
+/*
+ * Copyright (C) 2017 Robert Bosch. All Rights Reserved.
+ *
+ * Disclaimer
+ *
+ * Common:
+ * Bosch Sensortec products are developed for the consumer goods industry. They may only be used
+ * within the parameters of the respective valid product data sheet. Bosch Sensortec products are
+ * provided with the express understanding that there is no warranty of fitness for a particular purpose.
+ * They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
+ * that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
+ * Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
+ * The resale and/or use of products are at the purchasers own risk and his own responsibility. The
+ * examination of fitness for the intended use is the sole responsibility of the Purchaser.
+ *
+ * The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
+ * incidental, or consequential damages, arising from any product use not covered by the parameters of
+ * the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
+ * Sensortec for all costs in connection with such claims.
+ *
+ * The purchaser must monitor the market for the purchased products, particularly with regard to
+ * product safety and inform Bosch Sensortec without delay of all security relevant incidents.
+ *
+ * Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
+ * technical specifications of the product series. They are therefore not intended or fit for resale to third
+ * parties or for use in end products. Their sole purpose is internal client testing. The testing of an
+ * engineering sample may in no way replace the testing of a product series. Bosch Sensortec
+ * assumes no liability for the use of engineering samples. By accepting the engineering samples, the
+ * Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
+ * samples.
+ *
+ * Special:
+ * This software module (hereinafter called "Software") and any information on application-sheets
+ * (hereinafter called "Information") is provided free of charge for the sole purpose to support your
+ * application work. The Software and Information is subject to the following terms and conditions:
+ *
+ * The Software is specifically designed for the exclusive use for Bosch Sensortec products by
+ * personnel who have special experience and training. Do not use this Software if you do not have the
+ * proper experience or training.
+ *
+ * This Software package is provided `` as is `` and without any expressed or implied warranties,
+ * including without limitation, the implied warranties of merchantability and fitness for a particular
+ * purpose.
+ *
+ * Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
+ * of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
+ * representatives and agents shall not be liable for any direct or indirect damages or injury, except as
+ * otherwise stipulated in mandatory applicable law.
+ *
+ * The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
+ * responsibility for the consequences of use of such Information nor for any infringement of patents or
+ * other rights of third parties which may result from its use. No license is granted by implication or
+ * otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
+ * subject to change without notice.
+ *
+ * It is not allowed to deliver the source code of the Software to any third party without permission of
+ * Bosch Sensortec.
+ *
+ */
+
+/*!
+ * @file bsec_integration.c
+ *
+ * @brief
+ * Private part of the example for using of BSEC library.
+ */
+
+/*!
+ * @addtogroup bsec_examples BSEC Examples
+ * @brief BSEC usage examples
+ * @{*/
+
+/**********************************************************************************************************************/
+/* header files */
+/**********************************************************************************************************************/
+
+#include
+#include
+#include
+
+#include "bsec_integration.h"
+
+/**********************************************************************************************************************/
+/* local macro definitions */
+/**********************************************************************************************************************/
+
+#define NUM_USED_OUTPUTS 8
+
+/**********************************************************************************************************************/
+/* global variable declarations */
+/**********************************************************************************************************************/
+
+/* Global sensor APIs data structure */
+static struct bme680_dev bme680_g;
+
+/* Global temperature offset to be subtracted */
+static float bme680_temperature_offset_g = 0.0f;
+
+/**********************************************************************************************************************/
+/* functions */
+/**********************************************************************************************************************/
+
+/*!
+ * @brief Virtual sensor subscription
+ * Please call this function before processing of data using bsec_do_steps function
+ *
+ * @param[in] sample_rate mode to be used (either BSEC_SAMPLE_RATE_ULP or BSEC_SAMPLE_RATE_LP)
+ *
+ * @return subscription result, zero when successful
+ */
+static bsec_library_return_t bme680_bsec_update_subscription(float sample_rate)
+{
+ bsec_sensor_configuration_t requested_virtual_sensors[NUM_USED_OUTPUTS];
+ uint8_t n_requested_virtual_sensors = NUM_USED_OUTPUTS;
+
+ 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;
+
+ /* note: Virtual sensors as desired to be added here */
+ requested_virtual_sensors[0].sensor_id = BSEC_OUTPUT_IAQ;
+ requested_virtual_sensors[0].sample_rate = sample_rate;
+ requested_virtual_sensors[1].sensor_id = BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE;
+ requested_virtual_sensors[1].sample_rate = sample_rate;
+ requested_virtual_sensors[2].sensor_id = BSEC_OUTPUT_RAW_PRESSURE;
+ requested_virtual_sensors[2].sample_rate = sample_rate;
+ requested_virtual_sensors[3].sensor_id = BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY;
+ requested_virtual_sensors[3].sample_rate = sample_rate;
+ requested_virtual_sensors[4].sensor_id = BSEC_OUTPUT_RAW_GAS;
+ requested_virtual_sensors[4].sample_rate = sample_rate;
+ requested_virtual_sensors[5].sensor_id = BSEC_OUTPUT_RAW_TEMPERATURE;
+ requested_virtual_sensors[5].sample_rate = sample_rate;
+ requested_virtual_sensors[6].sensor_id = BSEC_OUTPUT_RAW_HUMIDITY;
+ requested_virtual_sensors[6].sample_rate = sample_rate;
+ requested_virtual_sensors[7].sensor_id = BSEC_OUTPUT_STATIC_IAQ;
+ requested_virtual_sensors[7].sample_rate = sample_rate;
+
+ /* 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);
+
+ return status;
+}
+
+/*!
+ * @brief Initialize the BME680 sensor and the BSEC library
+ *
+ * @param[in] sample_rate mode to be used (either BSEC_SAMPLE_RATE_ULP or BSEC_SAMPLE_RATE_LP)
+ * @param[in] temperature_offset device-specific temperature offset (due to self-heating)
+ * @param[in] bus_write pointer to the bus writing function
+ * @param[in] bus_read pointer to the bus reading function
+ * @param[in] sleep pointer to the system specific sleep function
+ * @param[in] state_load pointer to the system-specific state load function
+ * @param[in] config_load pointer to the system-specific config load function
+ *
+ * @return zero if successful, negative otherwise
+ */
+return_values_init bsec_iot_init(float sample_rate, float temperature_offset, bme680_com_fptr_t bus_write,
+ bme680_com_fptr_t bus_read, sleep_fct sleep, state_load_fct state_load, config_load_fct config_load)
+{
+ return_values_init ret = {BME680_OK, BSEC_OK};
+ bsec_library_return_t bsec_status = BSEC_OK;
+
+ uint8_t bsec_state[BSEC_MAX_PROPERTY_BLOB_SIZE] = {0};
+ uint8_t bsec_config[BSEC_MAX_PROPERTY_BLOB_SIZE] = {0};
+ uint8_t work_buffer[BSEC_MAX_PROPERTY_BLOB_SIZE] = {0};
+ int bsec_state_len, bsec_config_len;
+
+ /* Fixed I2C configuration */
+ bme680_g.dev_id = BME680_I2C_ADDR_PRIMARY;
+ bme680_g.intf = BME680_I2C_INTF;
+ /* User configurable I2C configuration */
+ bme680_g.write = bus_write;
+ bme680_g.read = bus_read;
+ bme680_g.delay_ms = sleep;
+
+ /* Initialize BME680 API */
+ ret.bme680_status = bme680_init(&bme680_g);
+ if (ret.bme680_status != BME680_OK)
+ {
+ return ret;
+ }
+
+ /* Initialize BSEC library */
+ ret.bsec_status = bsec_init();
+ if (ret.bsec_status != BSEC_OK)
+ {
+ return ret;
+ }
+
+ /* Load library config, if available */
+ bsec_config_len = config_load(bsec_config, sizeof(bsec_config));
+ if (bsec_config_len != 0)
+ {
+ ret.bsec_status = bsec_set_configuration(bsec_config, bsec_config_len, work_buffer, sizeof(work_buffer));
+ if (ret.bsec_status != BSEC_OK)
+ {
+ return ret;
+ }
+ }
+
+ /* Load previous library state, if available */
+ bsec_state_len = state_load(bsec_state, sizeof(bsec_state));
+ if (bsec_state_len != 0)
+ {
+ ret.bsec_status = bsec_set_state(bsec_state, bsec_state_len, work_buffer, sizeof(work_buffer));
+ if (ret.bsec_status != BSEC_OK)
+ {
+ return ret;
+ }
+ }
+
+ /* Set temperature offset */
+ bme680_temperature_offset_g = temperature_offset;
+
+ /* Call to the function which sets the library with subscription information */
+ ret.bsec_status = bme680_bsec_update_subscription(sample_rate);
+ if (ret.bsec_status != BSEC_OK)
+ {
+ return ret;
+ }
+
+ return ret;
+}
+
+/*!
+ * @brief Trigger the measurement based on sensor settings
+ *
+ * @param[in] sensor_settings settings of the BME680 sensor adopted by sensor control function
+ * @param[in] sleep pointer to the system specific sleep function
+ *
+ * @return none
+ */
+static void bme680_bsec_trigger_measurement(bsec_bme_settings_t *sensor_settings, sleep_fct sleep)
+{
+ uint16_t meas_period;
+ uint8_t set_required_settings;
+ int8_t bme680_status = BME680_OK;
+
+ /* Check if a forced-mode measurement should be triggered now */
+ if (sensor_settings->trigger_measurement)
+ {
+ /* Set sensor configuration */
+
+ bme680_g.tph_sett.os_hum = sensor_settings->humidity_oversampling;
+ bme680_g.tph_sett.os_pres = sensor_settings->pressure_oversampling;
+ bme680_g.tph_sett.os_temp = sensor_settings->temperature_oversampling;
+ bme680_g.gas_sett.run_gas = sensor_settings->run_gas;
+ bme680_g.gas_sett.heatr_temp = sensor_settings->heater_temperature; /* degree Celsius */
+ bme680_g.gas_sett.heatr_dur = sensor_settings->heating_duration; /* milliseconds */
+
+ /* Select the power mode */
+ /* Must be set before writing the sensor configuration */
+ bme680_g.power_mode = BME680_FORCED_MODE;
+ /* Set the required sensor settings needed */
+ set_required_settings = BME680_OST_SEL | BME680_OSP_SEL | BME680_OSH_SEL | BME680_GAS_SENSOR_SEL;
+
+ /* Set the desired sensor configuration */
+ bme680_status = bme680_set_sensor_settings(set_required_settings, &bme680_g);
+
+ /* Set power mode as forced mode and trigger forced mode measurement */
+ bme680_status = bme680_set_sensor_mode(&bme680_g);
+
+ /* Get the total measurement duration so as to sleep or wait till the measurement is complete */
+ bme680_get_profile_dur(&meas_period, &bme680_g);
+
+ /* Delay till the measurement is ready. Timestamp resolution in ms */
+ sleep((uint32_t)meas_period);
+ }
+
+ /* Call the API to get current operation mode of the sensor */
+ bme680_status = bme680_get_sensor_mode(&bme680_g);
+ /* When the measurement is completed and data is ready for reading, the sensor must be in BME680_SLEEP_MODE.
+ * Read operation mode to check whether measurement is completely done and wait until the sensor is no more
+ * in BME680_FORCED_MODE. */
+ while (bme680_g.power_mode == BME680_FORCED_MODE)
+ {
+ /* sleep for 5 ms */
+ sleep(5);
+ bme680_status = bme680_get_sensor_mode(&bme680_g);
+ }
+}
+
+/*!
+ * @brief Read the data from registers and populate the inputs structure to be passed to do_steps function
+ *
+ * @param[in] time_stamp_trigger settings of the sensor returned from sensor control function
+ * @param[in] inputs input structure containing the information on sensors to be passed to do_steps
+ * @param[in] num_bsec_inputs number of inputs to be passed to do_steps
+ * @param[in] bsec_process_data process data variable returned from sensor_control
+ *
+ * @return none
+ */
+static void bme680_bsec_read_data(int64_t time_stamp_trigger, bsec_input_t *inputs, uint8_t *num_bsec_inputs,
+ int32_t bsec_process_data)
+{
+ static struct bme680_field_data data;
+ int8_t bme680_status = BME680_OK;
+
+ /* We only have to read data if the previous call the bsec_sensor_control() actually asked for it */
+ if (bsec_process_data)
+ {
+ bme680_status = bme680_get_sensor_data(&data, &bme680_g);
+
+ if (data.status & BME680_NEW_DATA_MSK)
+ {
+ /* Pressure to be processed by BSEC */
+ if (bsec_process_data & BSEC_PROCESS_PRESSURE)
+ {
+ /* Place presssure sample into input struct */
+ inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_PRESSURE;
+ inputs[*num_bsec_inputs].signal = data.pressure;
+ inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
+ (*num_bsec_inputs)++;
+ }
+ /* Temperature to be processed by BSEC */
+ if (bsec_process_data & BSEC_PROCESS_TEMPERATURE)
+ {
+ /* Place temperature sample into input struct */
+ inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_TEMPERATURE;
+ #ifdef BME680_FLOAT_POINT_COMPENSATION
+ inputs[*num_bsec_inputs].signal = data.temperature;
+ #else
+ inputs[*num_bsec_inputs].signal = data.temperature / 100.0f;
+ #endif
+ inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
+ (*num_bsec_inputs)++;
+
+ /* Also add optional heatsource input which will be subtracted from the temperature reading to
+ * compensate for device-specific self-heating (supported in BSEC IAQ solution)*/
+ inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_HEATSOURCE;
+ inputs[*num_bsec_inputs].signal = bme680_temperature_offset_g;
+ inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
+ (*num_bsec_inputs)++;
+ }
+ /* Humidity to be processed by BSEC */
+ if (bsec_process_data & BSEC_PROCESS_HUMIDITY)
+ {
+ /* Place humidity sample into input struct */
+ inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_HUMIDITY;
+ #ifdef BME680_FLOAT_POINT_COMPENSATION
+ inputs[*num_bsec_inputs].signal = data.humidity;
+ #else
+ inputs[*num_bsec_inputs].signal = data.humidity / 1000.0f;
+ #endif
+ inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
+ (*num_bsec_inputs)++;
+ }
+ /* Gas to be processed by BSEC */
+ if (bsec_process_data & BSEC_PROCESS_GAS)
+ {
+ /* Check whether gas_valid flag is set */
+ if(data.status & BME680_GASM_VALID_MSK)
+ {
+ /* Place sample into input struct */
+ inputs[*num_bsec_inputs].sensor_id = BSEC_INPUT_GASRESISTOR;
+ inputs[*num_bsec_inputs].signal = data.gas_resistance;
+ inputs[*num_bsec_inputs].time_stamp = time_stamp_trigger;
+ (*num_bsec_inputs)++;
+ }
+ }
+ }
+ }
+}
+
+/*!
+ * @brief This function is written to process the sensor data for the requested virtual sensors
+ *
+ * @param[in] bsec_inputs input structure containing the information on sensors to be passed to do_steps
+ * @param[in] num_bsec_inputs number of inputs to be passed to do_steps
+ * @param[in] output_ready pointer to the function processing obtained BSEC outputs
+ *
+ * @return none
+ */
+static void bme680_bsec_process_data(bsec_input_t *bsec_inputs, uint8_t num_bsec_inputs, output_ready_fct output_ready)
+{
+ /* Output buffer set to the maximum virtual sensor outputs supported */
+ bsec_output_t bsec_outputs[BSEC_NUMBER_OUTPUTS];
+ uint8_t num_bsec_outputs = 0;
+ uint8_t index = 0;
+
+ bsec_library_return_t bsec_status = BSEC_OK;
+
+ int64_t timestamp = 0;
+ float iaq = 0.0f;
+ uint8_t iaq_accuracy = 0;
+ float temp = 0.0f;
+ float raw_temp = 0.0f;
+ float raw_pressure = 0.0f;
+ float humidity = 0.0f;
+ float raw_humidity = 0.0f;
+ float raw_gas = 0.0f;
+ float static_iaq = 0.0f;
+ uint8_t static_iaq_accuracy = 0;
+ float co2_equivalent = 0.0f;
+ uint8_t co2_accuracy = 0;
+ float breath_voc_equivalent = 0.0f;
+ uint8_t breath_voc_accuracy = 0;
+ float comp_gas_value = 0.0f;
+ uint8_t comp_gas_accuracy = 0;
+ float gas_percentage = 0.0f;
+ uint8_t gas_percentage_acccuracy = 0;
+
+ /* Check if something should be processed by BSEC */
+ if (num_bsec_inputs > 0)
+ {
+ /* Set number of outputs to the size of the allocated buffer */
+ /* BSEC_NUMBER_OUTPUTS to be defined */
+ num_bsec_outputs = BSEC_NUMBER_OUTPUTS;
+
+ /* Perform processing of the data by BSEC
+ Note:
+ * The number of outputs you get depends on what you asked for during bsec_update_subscription(). This is
+ handled under bme680_bsec_update_subscription() function in this example file.
+ * The number of actual outputs that are returned is written to num_bsec_outputs. */
+ bsec_status = bsec_do_steps(bsec_inputs, num_bsec_inputs, bsec_outputs, &num_bsec_outputs);
+
+ /* Iterate through the outputs and extract the relevant ones. */
+ for (index = 0; index < num_bsec_outputs; index++)
+ {
+ switch (bsec_outputs[index].sensor_id)
+ {
+ case BSEC_OUTPUT_IAQ:
+ iaq = bsec_outputs[index].signal;
+ iaq_accuracy = bsec_outputs[index].accuracy;
+ break;
+ case BSEC_OUTPUT_STATIC_IAQ:
+ static_iaq = bsec_outputs[index].signal;
+ static_iaq_accuracy = bsec_outputs[index].accuracy;
+ break;
+ case BSEC_OUTPUT_CO2_EQUIVALENT:
+ co2_equivalent = bsec_outputs[index].signal;
+ co2_accuracy = bsec_outputs[index].accuracy;
+ break;
+ case BSEC_OUTPUT_BREATH_VOC_EQUIVALENT:
+ breath_voc_equivalent = bsec_outputs[index].signal;
+ breath_voc_accuracy = bsec_outputs[index].accuracy;
+ break;
+ case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_TEMPERATURE:
+ temp = bsec_outputs[index].signal;
+ break;
+ case BSEC_OUTPUT_RAW_PRESSURE:
+ raw_pressure = bsec_outputs[index].signal;
+ break;
+ case BSEC_OUTPUT_SENSOR_HEAT_COMPENSATED_HUMIDITY:
+ humidity = bsec_outputs[index].signal;
+ break;
+ case BSEC_OUTPUT_RAW_GAS:
+ raw_gas = bsec_outputs[index].signal;
+ break;
+ case BSEC_OUTPUT_RAW_TEMPERATURE:
+ raw_temp = bsec_outputs[index].signal;
+ break;
+ case BSEC_OUTPUT_RAW_HUMIDITY:
+ raw_humidity = bsec_outputs[index].signal;
+ break;
+ case BSEC_OUTPUT_COMPENSATED_GAS:
+ comp_gas_value = bsec_outputs[index].signal;
+ comp_gas_accuracy = bsec_outputs[index].accuracy;
+ break;
+ case BSEC_OUTPUT_GAS_PERCENTAGE:
+ gas_percentage = bsec_outputs[index].signal;
+ gas_percentage_acccuracy = bsec_outputs[index].accuracy;
+ break;
+ default:
+ continue;
+ }
+
+ /* Assume that all the returned timestamps are the same */
+ timestamp = bsec_outputs[index].time_stamp;
+ }
+
+ /* Pass the extracted outputs to the user provided output_ready() function. */
+ output_ready(timestamp, iaq, iaq_accuracy, temp, humidity, raw_pressure, raw_temp,
+ raw_humidity, raw_gas, bsec_status, static_iaq, co2_equivalent, breath_voc_equivalent);
+ }
+}
+
+/*!
+ * @brief Runs the main (endless) loop that queries sensor settings, applies them, and processes the measured data
+ *
+ * @param[in] sleep pointer to the system specific sleep function
+ * @param[in] get_timestamp_us pointer to the system specific timestamp derivation function
+ * @param[in] output_ready pointer to the function processing obtained BSEC outputs
+ * @param[in] state_save pointer to the system-specific state save function
+ * @param[in] save_intvl interval at which BSEC state should be saved (in samples)
+ *
+ * @return none
+ */
+void bsec_iot_loop(sleep_fct sleep, get_timestamp_us_fct get_timestamp_us, output_ready_fct output_ready,
+ state_save_fct state_save, uint32_t save_intvl)
+{
+ /* Timestamp variables */
+ int64_t time_stamp = 0;
+ int64_t time_stamp_interval_ms = 0;
+
+ /* Allocate enough memory for up to BSEC_MAX_PHYSICAL_SENSOR physical inputs*/
+ bsec_input_t bsec_inputs[BSEC_MAX_PHYSICAL_SENSOR];
+
+ /* Number of inputs to BSEC */
+ uint8_t num_bsec_inputs = 0;
+
+ /* BSEC sensor settings struct */
+ bsec_bme_settings_t sensor_settings;
+
+ /* Save state variables */
+ uint8_t bsec_state[BSEC_MAX_STATE_BLOB_SIZE];
+ uint8_t work_buffer[BSEC_MAX_STATE_BLOB_SIZE];
+ uint32_t bsec_state_len = 0;
+ uint32_t n_samples = 0;
+
+ bsec_library_return_t bsec_status = BSEC_OK;
+
+ while (1)
+ {
+ /* get the timestamp in nanoseconds before calling bsec_sensor_control() */
+ time_stamp = get_timestamp_us() * 1000;
+
+ /* Retrieve sensor settings to be used in this time instant by calling bsec_sensor_control */
+ bsec_sensor_control(time_stamp, &sensor_settings);
+
+ /* Trigger a measurement if necessary */
+ bme680_bsec_trigger_measurement(&sensor_settings, sleep);
+
+ /* Read data from last measurement */
+ num_bsec_inputs = 0;
+ bme680_bsec_read_data(time_stamp, bsec_inputs, &num_bsec_inputs, sensor_settings.process_data);
+
+ /* Time to invoke BSEC to perform the actual processing */
+ bme680_bsec_process_data(bsec_inputs, num_bsec_inputs, output_ready);
+
+ /* Increment sample counter */
+ n_samples++;
+
+ /* Retrieve and store state if the passed save_intvl */
+ if (n_samples >= save_intvl)
+ {
+ bsec_status = bsec_get_state(0, bsec_state, sizeof(bsec_state), work_buffer, sizeof(work_buffer), &bsec_state_len);
+ if (bsec_status == BSEC_OK)
+ {
+ state_save(bsec_state, bsec_state_len);
+ }
+ n_samples = 0;
+ }
+
+
+ /* Compute how long we can sleep until we need to call bsec_sensor_control() next */
+ /* Time_stamp is converted from microseconds to nanoseconds first and then the difference to milliseconds */
+ time_stamp_interval_ms = (sensor_settings.next_call - get_timestamp_us() * 1000) / 1000000;
+ if (time_stamp_interval_ms > 0)
+ {
+ sleep((uint32_t)time_stamp_interval_ms);
+ }
+ }
+}
+
+/*! @}*/
+
diff --git a/lib/Bosch-BSEC/bsec_integration.h b/lib/Bosch-BSEC/bsec_integration.h
new file mode 100644
index 00000000..5155a001
--- /dev/null
+++ b/lib/Bosch-BSEC/bsec_integration.h
@@ -0,0 +1,165 @@
+/*
+ * Copyright (C) 2017 Robert Bosch. All Rights Reserved.
+ *
+ * Disclaimer
+ *
+ * Common:
+ * Bosch Sensortec products are developed for the consumer goods industry. They may only be used
+ * within the parameters of the respective valid product data sheet. Bosch Sensortec products are
+ * provided with the express understanding that there is no warranty of fitness for a particular purpose.
+ * They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
+ * that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
+ * Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
+ * The resale and/or use of products are at the purchasers own risk and his own responsibility. The
+ * examination of fitness for the intended use is the sole responsibility of the Purchaser.
+ *
+ * The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
+ * incidental, or consequential damages, arising from any product use not covered by the parameters of
+ * the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
+ * Sensortec for all costs in connection with such claims.
+ *
+ * The purchaser must monitor the market for the purchased products, particularly with regard to
+ * product safety and inform Bosch Sensortec without delay of all security relevant incidents.
+ *
+ * Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
+ * technical specifications of the product series. They are therefore not intended or fit for resale to third
+ * parties or for use in end products. Their sole purpose is internal client testing. The testing of an
+ * engineering sample may in no way replace the testing of a product series. Bosch Sensortec
+ * assumes no liability for the use of engineering samples. By accepting the engineering samples, the
+ * Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
+ * samples.
+ *
+ * Special:
+ * This software module (hereinafter called "Software") and any information on application-sheets
+ * (hereinafter called "Information") is provided free of charge for the sole purpose to support your
+ * application work. The Software and Information is subject to the following terms and conditions:
+ *
+ * The Software is specifically designed for the exclusive use for Bosch Sensortec products by
+ * personnel who have special experience and training. Do not use this Software if you do not have the
+ * proper experience or training.
+ *
+ * This Software package is provided `` as is `` and without any expressed or implied warranties,
+ * including without limitation, the implied warranties of merchantability and fitness for a particular
+ * purpose.
+ *
+ * Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
+ * of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
+ * representatives and agents shall not be liable for any direct or indirect damages or injury, except as
+ * otherwise stipulated in mandatory applicable law.
+ *
+ * The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
+ * responsibility for the consequences of use of such Information nor for any infringement of patents or
+ * other rights of third parties which may result from its use. No license is granted by implication or
+ * otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
+ * subject to change without notice.
+ *
+ * It is not allowed to deliver the source code of the Software to any third party without permission of
+ * Bosch Sensortec.
+ *
+ */
+
+/*!
+ * @file bsec_integration.h
+ *
+ * @brief
+ * Contains BSEC integration API
+ */
+
+/*!
+ * @addtogroup bsec_examples BSEC Examples
+ * @brief BSEC usage examples
+ * @{*/
+
+#ifndef __BSEC_INTEGRATION_H__
+#define __BSEC_INTEGRATION_H__
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+/**********************************************************************************************************************/
+/* header files */
+/**********************************************************************************************************************/
+
+/* Use the following bme680 driver: https://github.com/BoschSensortec/BME680_driver/releases/tag/bme680_v3.5.1 */
+#include "bme680.h"
+/* BSEC header files are available in the inc/ folder of the release package */
+#include "bsec_interface.h"
+#include "bsec_datatypes.h"
+
+
+/**********************************************************************************************************************/
+/* type definitions */
+/**********************************************************************************************************************/
+
+/* function pointer to the system specific sleep function */
+typedef void (*sleep_fct)(uint32_t t_ms);
+
+/* function pointer to the system specific timestamp derivation function */
+typedef int64_t (*get_timestamp_us_fct)();
+
+/* function pointer to the function processing obtained BSEC outputs */
+typedef void (*output_ready_fct)(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);
+
+/* function pointer to the function loading a previous BSEC state from NVM */
+typedef uint32_t (*state_load_fct)(uint8_t *state_buffer, uint32_t n_buffer);
+
+/* function pointer to the function saving BSEC state to NVM */
+typedef void (*state_save_fct)(const uint8_t *state_buffer, uint32_t length);
+
+/* function pointer to the function loading the BSEC configuration string from NVM */
+typedef uint32_t (*config_load_fct)(uint8_t *state_buffer, uint32_t n_buffer);
+
+/* structure definitions */
+
+/* Structure with the return value from bsec_iot_init() */
+typedef struct{
+ /*! Result of API execution status */
+ int8_t bme680_status;
+ /*! Result of BSEC library */
+ bsec_library_return_t bsec_status;
+}return_values_init;
+/**********************************************************************************************************************/
+/* function declarations */
+/**********************************************************************************************************************/
+
+/*!
+ * @brief Initialize the BME680 sensor and the BSEC library
+ *
+ * @param[in] sample_rate mode to be used (either BSEC_SAMPLE_RATE_ULP or BSEC_SAMPLE_RATE_LP)
+ * @param[in] temperature_offset device-specific temperature offset (due to self-heating)
+ * @param[in] bus_write pointer to the bus writing function
+ * @param[in] bus_read pointer to the bus reading function
+ * @param[in] sleep pointer to the system-specific sleep function
+ * @param[in] state_load pointer to the system-specific state load function
+ *
+ * @return zero if successful, negative otherwise
+ */
+return_values_init bsec_iot_init(float sample_rate, float temperature_offset, bme680_com_fptr_t bus_write, bme680_com_fptr_t bus_read,
+ sleep_fct sleep, state_load_fct state_load, config_load_fct config_load);
+
+/*!
+ * @brief Runs the main (endless) loop that queries sensor settings, applies them, and processes the measured data
+ *
+ * @param[in] sleep pointer to the system-specific sleep function
+ * @param[in] get_timestamp_us pointer to the system-specific timestamp derivation function
+ * @param[in] output_ready pointer to the function processing obtained BSEC outputs
+ * @param[in] state_save pointer to the system-specific state save function
+ * @param[in] save_intvl interval at which BSEC state should be saved (in samples)
+ *
+ * @return return_values_init struct with the result of the API and the BSEC library
+ */
+void bsec_iot_loop(sleep_fct sleep, get_timestamp_us_fct get_timestamp_us, output_ready_fct output_ready,
+ state_save_fct state_save, uint32_t save_intvl);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __BSEC_INTEGRATION_H__ */
+
+/*! @}*/
+
diff --git a/lib/Bosch-BSEC/bsec_interface.h b/lib/Bosch-BSEC/bsec_interface.h
new file mode 100644
index 00000000..ef68eb15
--- /dev/null
+++ b/lib/Bosch-BSEC/bsec_interface.h
@@ -0,0 +1,564 @@
+/*
+ * Copyright (C) 2015, 2016, 2017 Robert Bosch. All Rights Reserved.
+ *
+ * Disclaimer
+ *
+ * Common:
+ * Bosch Sensortec products are developed for the consumer goods industry. They may only be used
+ * within the parameters of the respective valid product data sheet. Bosch Sensortec products are
+ * provided with the express understanding that there is no warranty of fitness for a particular purpose.
+ * They are not fit for use in life-sustaining, safety or security sensitive systems or any system or device
+ * that may lead to bodily harm or property damage if the system or device malfunctions. In addition,
+ * Bosch Sensortec products are not fit for use in products which interact with motor vehicle systems.
+ * The resale and/or use of products are at the purchasers own risk and his own responsibility. The
+ * examination of fitness for the intended use is the sole responsibility of the Purchaser.
+ *
+ * The purchaser shall indemnify Bosch Sensortec from all third party claims, including any claims for
+ * incidental, or consequential damages, arising from any product use not covered by the parameters of
+ * the respective valid product data sheet or not approved by Bosch Sensortec and reimburse Bosch
+ * Sensortec for all costs in connection with such claims.
+ *
+ * The purchaser must monitor the market for the purchased products, particularly with regard to
+ * product safety and inform Bosch Sensortec without delay of all security relevant incidents.
+ *
+ * Engineering Samples are marked with an asterisk (*) or (e). Samples may vary from the valid
+ * technical specifications of the product series. They are therefore not intended or fit for resale to third
+ * parties or for use in end products. Their sole purpose is internal client testing. The testing of an
+ * engineering sample may in no way replace the testing of a product series. Bosch Sensortec
+ * assumes no liability for the use of engineering samples. By accepting the engineering samples, the
+ * Purchaser agrees to indemnify Bosch Sensortec from all claims arising from the use of engineering
+ * samples.
+ *
+ * Special:
+ * This software module (hereinafter called "Software") and any information on application-sheets
+ * (hereinafter called "Information") is provided free of charge for the sole purpose to support your
+ * application work. The Software and Information is subject to the following terms and conditions:
+ *
+ * The Software is specifically designed for the exclusive use for Bosch Sensortec products by
+ * personnel who have special experience and training. Do not use this Software if you do not have the
+ * proper experience or training.
+ *
+ * This Software package is provided `` as is `` and without any expressed or implied warranties,
+ * including without limitation, the implied warranties of merchantability and fitness for a particular
+ * purpose.
+ *
+ * Bosch Sensortec and their representatives and agents deny any liability for the functional impairment
+ * of this Software in terms of fitness, performance and safety. Bosch Sensortec and their
+ * representatives and agents shall not be liable for any direct or indirect damages or injury, except as
+ * otherwise stipulated in mandatory applicable law.
+ *
+ * The Information provided is believed to be accurate and reliable. Bosch Sensortec assumes no
+ * responsibility for the consequences of use of such Information nor for any infringement of patents or
+ * other rights of third parties which may result from its use. No license is granted by implication or
+ * otherwise under any patent or patent rights of Bosch. Specifications mentioned in the Information are
+ * subject to change without notice.
+ *
+ * It is not allowed to deliver the source code of the Software to any third party without permission of
+ * Bosch Sensortec.
+ *
+ */
+ /*!
+ *
+ * @file bsec_interface.h
+ *
+ * @brief
+ * Contains the API for BSEC
+ *
+ */
+
+
+#ifndef __BSEC_INTERFACE_H__
+#define __BSEC_INTERFACE_H__
+
+#include "bsec_datatypes.h"
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+
+ /*! @addtogroup bsec_interface BSEC C Interface
+ * @brief Interfaces of BSEC signal processing library
+ *
+ * ### Interface usage
+ *
+ * The following provides a short overview on the typical operation sequence for BSEC.
+ *
+ * - Initialization of the library
+ *
+ * | Steps | Function |
+ * |---------------------------------------------------------------------|--------------------------|
+ * | Initialization of library | bsec_init() |
+ * | Update configuration settings (optional) | bsec_set_configuration() |
+ * | Restore the state of the library (optional) | bsec_set_state() |
+ *
+ *
+ * - The following function is called to enable output signals and define their sampling rate / operation mode.
+ *
+ * | Steps | Function |
+ * |---------------------------------------------|----------------------------|
+ * | Enable library outputs with specified mode | bsec_update_subscription() |
+ *
+ *
+ * - This table describes the main processing loop.
+ *
+ * | Steps | Function |
+ * |-------------------------------------------|----------------------------------|
+ * | Retrieve sensor settings to be used | bsec_sensor_control() |
+ * | Configure sensor and trigger measurement | See BME680 API and example codes |
+ * | Read results from sensor | See BME680 API and example codes |
+ * | Perform signal processing | bsec_do_steps() |
+ *
+ *
+ * - Before shutting down the system, the current state of BSEC can be retrieved and can then be used during
+ * re-initialization to continue processing.
+ *
+ * | Steps | Function |
+ * |----------------------------------------|-------------------|
+ * | To retrieve the current library state | bsec_get_state() |
+ *
+ *
+ *
+ * ### Configuration and state
+ *
+ * Values of variables belonging to a BSEC instance are divided into two groups:
+ * - Values **not updated by processing** of signals belong to the **configuration group**. If available, BSEC can be
+ * configured before use with a customer specific configuration string.
+ * - Values **updated during processing** are member of the **state group**. Saving and restoring of the state of BSEC
+ * is necessary to maintain previously estimated sensor models and baseline information which is important for best
+ * performance of the gas sensor outputs.
+ *
+ * @note BSEC library consists of adaptive algorithms which models the gas sensor which improves its performance over
+ * the time. These will be lost if library is initialized due to system reset. In order to avoid this situation
+ * library state shall be stored in non volatile memory so that it can be loaded after system reset.
+ *
+ *
+ * @{
+ */
+
+
+/*!
+ * @brief Return the version information of BSEC library
+ *
+ * @param [out] bsec_version_p pointer to struct which is to be populated with the version information
+ *
+ * @return Zero if successful, otherwise an error code
+ *
+ * See also: bsec_version_t
+ *
+ \code{.c}
+ // Example //
+ bsec_version_t version;
+ bsec_get_version(&version);
+ printf("BSEC version: %d.%d.%d.%d",version.major, version.minor, version.major_bugfix, version.minor_bugfix);
+
+ \endcode
+*/
+
+bsec_library_return_t bsec_get_version(bsec_version_t * bsec_version_p);
+
+
+/*!
+ * @brief Initialize the library
+ *
+ * Initialization and reset of BSEC is performed by calling bsec_init(). Calling this function sets up the relation
+ * among all internal modules, initializes run-time dependent library states and resets the configuration and state
+ * of all BSEC signal processing modules to defaults.
+ *
+ * Before any further use, the library must be initialized. This ensure that all memory and states are in defined
+ * conditions prior to processing any data.
+ *
+ * @return Zero if successful, otherwise an error code
+ *
+ \code{.c}
+
+ // Initialize BSEC library before further use
+ bsec_init();
+
+ \endcode
+*/
+
+bsec_library_return_t bsec_init(void);
+
+/*!
+ * @brief Subscribe to library virtual sensors outputs
+ *
+ * Use bsec_update_subscription() to instruct BSEC which of the processed output signals are requested at which sample rates.
+ * See ::bsec_virtual_sensor_t for available library outputs.
+ *
+ * Based on the requested virtual sensors outputs, BSEC will provide information about the required physical sensor input signals
+ * (see ::bsec_physical_sensor_t) with corresponding sample rates. This information is purely informational as bsec_sensor_control()
+ * will ensure the sensor is operated in the required manner. To disable a virtual sensor, set the sample rate to BSEC_SAMPLE_RATE_DISABLED.
+ *
+ * The subscription update using bsec_update_subscription() is apart from the signal processing one of the the most
+ * important functions. It allows to enable the desired library outputs. The function determines which physical input
+ * sensor signals are required at which sample rate to produce the virtual output sensor signals requested by the user.
+ * When this function returns with success, the requested outputs are called subscribed. A very important feature is the
+ * retaining of already subscribed outputs. Further outputs can be requested or disabled both individually and
+ * group-wise in addition to already subscribed outputs without changing them unless a change of already subscribed
+ * outputs is requested.
+ *
+ * @note The state of the library concerning the subscribed outputs cannot be retained among reboots.
+ *
+ * The interface of bsec_update_subscription() requires the usage of arrays of sensor configuration structures.
+ * Such a structure has the fields sensor identifier and sample rate. These fields have the properties:
+ * - Output signals of virtual sensors must be requested using unique identifiers (Member of ::bsec_virtual_sensor_t)
+ * - Different sets of identifiers are available for inputs of physical sensors and outputs of virtual sensors
+ * - Identifiers are unique values defined by the library, not from external
+ * - Sample rates must be provided as value of
+ * - An allowed sample rate for continuously sampled signals
+ * - 65535.0f (BSEC_SAMPLE_RATE_DISABLED) to turn off outputs and identify disabled inputs
+ *
+ * @note The same sensor identifiers are also used within the functions bsec_do_steps().
+ *
+ * The usage principles of bsec_update_subscription() are:
+ * - Differential updates (i.e., only asking for outputs that the user would like to change) is supported.
+ * - Invalid requests of outputs are ignored. Also if one of the requested outputs is unavailable, all the requests
+ * are ignored. At the same time, a warning is returned.
+ * - To disable BSEC, all outputs shall be turned off. Only enabled (subscribed) outputs have to be disabled while
+ * already disabled outputs do not have to be disabled explicitly.
+ *
+ * @param[in] requested_virtual_sensors Pointer to array of requested virtual sensor (output) configurations for the library
+ * @param[in] n_requested_virtual_sensors Number of virtual sensor structs pointed by requested_virtual_sensors
+ * @param[out] required_sensor_settings Pointer to array of required physical sensor configurations for the library
+ * @param[in,out] n_required_sensor_settings [in] Size of allocated required_sensor_settings array, [out] number of sensor configurations returned
+ *
+ * @return Zero when successful, otherwise an error code
+ *
+ * @sa bsec_sensor_configuration_t
+ * @sa bsec_physical_sensor_t
+ * @sa bsec_virtual_sensor_t
+ *
+ \code{.c}
+ // Example //
+
+ // Change 3 virtual sensors (switch IAQ and raw temperature -> on / pressure -> off)
+ bsec_sensor_configuration_t requested_virtual_sensors[3];
+ uint8_t n_requested_virtual_sensors = 3;
+
+ requested_virtual_sensors[0].sensor_id = BSEC_OUTPUT_IAQ;
+ requested_virtual_sensors[0].sample_rate = BSEC_SAMPLE_RATE_ULP;
+ requested_virtual_sensors[1].sensor_id = BSEC_OUTPUT_RAW_TEMPERATURE;
+ requested_virtual_sensors[1].sample_rate = BSEC_SAMPLE_RATE_ULP;
+ requested_virtual_sensors[2].sensor_id = BSEC_OUTPUT_RAW_PRESSURE;
+ requested_virtual_sensors[2].sample_rate = BSEC_SAMPLE_RATE_DISABLED;
+
+ // Allocate a struct for the returned physical sensor settings
+ bsec_sensor_configuration_t required_sensor_settings[BSEC_MAX_PHYSICAL_SENSOR];
+ uint8_t n_required_sensor_settings = BSEC_MAX_PHYSICAL_SENSOR;
+
+ // Call bsec_update_subscription() to enable/disable the requested virtual sensors
+ bsec_update_subscription(requested_virtual_sensors, n_requested_virtual_sensors, required_sensor_settings, &n_required_sensor_settings);
+ \endcode
+ *
+ */
+bsec_library_return_t bsec_update_subscription(const bsec_sensor_configuration_t * const requested_virtual_sensors,
+ const uint8_t n_requested_virtual_sensors, bsec_sensor_configuration_t * required_sensor_settings,
+ uint8_t * n_required_sensor_settings);
+
+
+/*!
+ * @brief Main signal processing function of BSEC
+ *
+ *
+ * Processing of the input signals and returning of output samples is performed by bsec_do_steps().
+ * - The samples of all library inputs must be passed with unique identifiers representing the input signals from
+ * physical sensors where the order of these inputs can be chosen arbitrary. However, all input have to be provided
+ * within the same time period as they are read. A sequential provision to the library might result in undefined
+ * behavior.
+ * - The samples of all library outputs are returned with unique identifiers corresponding to the output signals of
+ * virtual sensors where the order of the returned outputs may be arbitrary.
+ * - The samples of all input as well as output signals of physical as well as virtual sensors use the same
+ * representation in memory with the following fields:
+ * - Sensor identifier:
+ * - For inputs: required to identify the input signal from a physical sensor
+ * - For output: overwritten by bsec_do_steps() to identify the returned signal from a virtual sensor
+ * - Time stamp of the sample
+ *
+ * Calling bsec_do_steps() requires the samples of the input signals to be provided along with their time stamp when
+ * they are recorded and only when they are acquired. Repetition of samples with the same time stamp are ignored and
+ * result in a warning. Repetition of values of samples which are not acquired anew by a sensor result in deviations
+ * of the computed output signals. Concerning the returned output samples, an important feature is, that a value is
+ * returned for an output only when a new occurrence has been computed. A sample of an output signal is returned only
+ * once.
+ *
+ *
+ * @param[in] inputs Array of input data samples. Each array element represents a sample of a different physical sensor.
+ * @param[in] n_inputs Number of passed input data structs.
+ * @param[out] outputs Array of output data samples. Each array element represents a sample of a different virtual sensor.
+ * @param[in,out] n_outputs [in] Number of allocated output structs, [out] number of outputs returned
+ *
+ * @return Zero when successful, otherwise an error code
+ *
+
+ \code{.c}
+ // Example //
+
+ // Allocate input and output memory
+ bsec_input_t input[3];
+ uint8_t n_input = 3;
+ bsec_output_t output[2];
+ uint8_t n_output=2;
+
+ bsec_library_return_t status;
+
+ // Populate the input structs, assuming the we have timestamp (ts),
+ // gas sensor resistance (R), temperature (T), and humidity (rH) available
+ // as input variables
+ input[0].sensor_id = BSEC_INPUT_GASRESISTOR;
+ input[0].signal = R;
+ input[0].time_stamp= ts;
+ input[1].sensor_id = BSEC_INPUT_TEMPERATURE;
+ input[1].signal = T;
+ input[1].time_stamp= ts;
+ input[2].sensor_id = BSEC_INPUT_HUMIDITY;
+ input[2].signal = rH;
+ input[2].time_stamp= ts;
+
+
+ // Invoke main processing BSEC function
+ status = bsec_do_steps( input, n_input, output, &n_output );
+
+ // Iterate through the BSEC output data, if the call succeeded
+ if(status == BSEC_OK)
+ {
+ for(int i = 0; i < n_output; i++)
+ {
+ switch(output[i].sensor_id)
+ {
+ case BSEC_OUTPUT_IAQ:
+ // Retrieve the IAQ results from output[i].signal
+ // and do something with the data
+ break;
+ case BSEC_OUTPUT_AMBIENT_TEMPERATURE:
+ // Retrieve the ambient temperature results from output[i].signal
+ // and do something with the data
+ break;
+
+ }
+ }
+ }
+
+ \endcode
+ */
+
+bsec_library_return_t bsec_do_steps(const bsec_input_t * const inputs, const uint8_t n_inputs, bsec_output_t * outputs, uint8_t * n_outputs);
+
+
+/*!
+ * @brief Reset a particular virtual sensor output
+ *
+ * This function allows specific virtual sensor outputs to be reset. The meaning of "reset" depends on the specific
+ * output. In case of the IAQ output, reset means zeroing the output to the current ambient conditions.
+ *
+ * @param[in] sensor_id Virtual sensor to be reset
+ *
+ * @return Zero when successful, otherwise an error code
+ *
+ *
+ \code{.c}
+ // Example //
+ bsec_reset_output(BSEC_OUTPUT_IAQ);
+
+ \endcode
+ */
+
+bsec_library_return_t bsec_reset_output(uint8_t sensor_id);
+
+
+/*!
+ * @brief Update algorithm configuration parameters
+ *
+ * BSEC uses a default configuration for the modules and common settings. The initial configuration can be customized
+ * by bsec_set_configuration(). This is an optional step.
+ *
+ * @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose
+ * the serialization and apply it to the library and its modules. Please use #BSEC_MAX_PROPERTY_BLOB_SIZE for allotting
+ * the required size.
+ *
+ * @param[in] serialized_settings Settings serialized to a binary blob
+ * @param[in] n_serialized_settings Size of the settings blob
+ * @param[in,out] work_buffer Work buffer used to parse the blob
+ * @param[in] n_work_buffer_size Length of the work buffer available for parsing the blob
+ *
+ * @return Zero when successful, otherwise an error code
+ *
+ \code{.c}
+ // Example //
+
+ // Allocate variables
+ uint8_t serialized_settings[BSEC_MAX_PROPERTY_BLOB_SIZE];
+ uint32_t n_serialized_settings_max = BSEC_MAX_PROPERTY_BLOB_SIZE;
+ uint8_t work_buffer[BSEC_MAX_PROPERTY_BLOB_SIZE];
+ uint32_t n_work_buffer = BSEC_MAX_PROPERTY_BLOB_SIZE;
+
+ // Here we will load a provided config string into serialized_settings
+
+ // Apply the configuration
+ bsec_set_configuration(serialized_settings, n_serialized_settings_max, work_buffer, n_work_buffer);
+
+ \endcode
+ */
+
+bsec_library_return_t bsec_set_configuration(const uint8_t * const serialized_settings,
+ const uint32_t n_serialized_settings, uint8_t * work_buffer,
+ const uint32_t n_work_buffer_size);
+
+
+/*!
+ * @brief Restore the internal state of the library
+ *
+ * BSEC uses a default state for all signal processing modules and the BSEC module. To ensure optimal performance,
+ * especially of the gas sensor functionality, it is recommended to retrieve the state using bsec_get_state()
+ * before unloading the library, storing it in some form of non-volatile memory, and setting it using bsec_set_state()
+ * before resuming further operation of the library.
+ *
+ * @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose the
+ * serialization and apply it to the library and its modules. Please use #BSEC_MAX_PROPERTY_BLOB_SIZE for allotting the
+ * required size.
+ *
+ * @param[in] serialized_state States serialized to a binary blob
+ * @param[in] n_serialized_state Size of the state blob
+ * @param[in,out] work_buffer Work buffer used to parse the blob
+ * @param[in] n_work_buffer_size Length of the work buffer available for parsing the blob
+ *
+ * @return Zero when successful, otherwise an error code
+ *
+ \code{.c}
+ // Example //
+
+ // Allocate variables
+ uint8_t serialized_state[BSEC_MAX_PROPERTY_BLOB_SIZE];
+ uint32_t n_serialized_state = BSEC_MAX_PROPERTY_BLOB_SIZE;
+ uint8_t work_buffer_state[BSEC_MAX_PROPERTY_BLOB_SIZE];
+ uint32_t n_work_buffer_size = BSEC_MAX_PROPERTY_BLOB_SIZE;
+
+ // Here we will load a state string from a previous use of BSEC
+
+ // Apply the previous state to the current BSEC session
+ bsec_set_state(serialized_state, n_serialized_state, work_buffer_state, n_work_buffer_size);
+
+ \endcode
+*/
+
+bsec_library_return_t bsec_set_state(const uint8_t * const serialized_state, const uint32_t n_serialized_state,
+ uint8_t * work_buffer, const uint32_t n_work_buffer_size);
+
+
+/*!
+ * @brief Retrieve the current library configuration
+ *
+ * BSEC allows to retrieve the current configuration using bsec_get_configuration(). Returns a binary blob encoding
+ * the current configuration parameters of the library in a format compatible with bsec_set_configuration().
+ *
+ * @note The function bsec_get_configuration() is required to be used for debugging purposes only.
+ * @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose the
+ * serialization and apply it to the library and its modules. Please use #BSEC_MAX_PROPERTY_BLOB_SIZE for allotting the
+ * required size.
+ *
+ *
+ * @param[in] config_id Identifier for a specific set of configuration settings to be returned;
+ * shall be zero to retrieve all configuration settings.
+ * @param[out] serialized_settings Buffer to hold the serialized config blob
+ * @param[in] n_serialized_settings_max Maximum available size for the serialized settings
+ * @param[in,out] work_buffer Work buffer used to parse the binary blob
+ * @param[in] n_work_buffer Length of the work buffer available for parsing the blob
+ * @param[out] n_serialized_settings Actual size of the returned serialized configuration blob
+ *
+ * @return Zero when successful, otherwise an error code
+ *
+ \code{.c}
+ // Example //
+
+ // Allocate variables
+ uint8_t serialized_settings[BSEC_MAX_PROPERTY_BLOB_SIZE];
+ uint32_t n_serialized_settings_max = BSEC_MAX_PROPERTY_BLOB_SIZE;
+ uint8_t work_buffer[BSEC_MAX_PROPERTY_BLOB_SIZE];
+ uint32_t n_work_buffer = BSEC_MAX_PROPERTY_BLOB_SIZE;
+ uint32_t n_serialized_settings = 0;
+
+ // Configuration of BSEC algorithm is stored in 'serialized_settings'
+ bsec_get_configuration(0, serialized_settings, n_serialized_settings_max, work_buffer, n_work_buffer, &n_serialized_settings);
+
+ \endcode
+ */
+
+bsec_library_return_t bsec_get_configuration(const uint8_t config_id, uint8_t * serialized_settings, const uint32_t n_serialized_settings_max,
+ uint8_t * work_buffer, const uint32_t n_work_buffer, uint32_t * n_serialized_settings);
+
+
+/*!
+ *@brief Retrieve the current internal library state
+ *
+ * BSEC allows to retrieve the current states of all signal processing modules and the BSEC module using
+ * bsec_get_state(). This allows a restart of the processing after a reboot of the system by calling bsec_set_state().
+ *
+ * @note A work buffer with sufficient size is required and has to be provided by the function caller to decompose the
+ * serialization and apply it to the library and its modules. Please use #BSEC_MAX_STATE_BLOB_SIZE for allotting the
+ * required size.
+ *
+ *
+ * @param[in] state_set_id Identifier for a specific set of states to be returned; shall be
+ * zero to retrieve all states.
+ * @param[out] serialized_state Buffer to hold the serialized config blob
+ * @param[in] n_serialized_state_max Maximum available size for the serialized states
+ * @param[in,out] work_buffer Work buffer used to parse the blob
+ * @param[in] n_work_buffer Length of the work buffer available for parsing the blob
+ * @param[out] n_serialized_state Actual size of the returned serialized blob
+ *
+ * @return Zero when successful, otherwise an error code
+ *
+ \code{.c}
+ // Example //
+
+ // Allocate variables
+ uint8_t serialized_state[BSEC_MAX_STATE_BLOB_SIZE];
+ uint32_t n_serialized_state_max = BSEC_MAX_STATE_BLOB_SIZE;
+ uint32_t n_serialized_state = BSEC_MAX_STATE_BLOB_SIZE;
+ uint8_t work_buffer_state[BSEC_MAX_STATE_BLOB_SIZE];
+ uint32_t n_work_buffer_size = BSEC_MAX_STATE_BLOB_SIZE;
+
+ // Algorithm state is stored in 'serialized_state'
+ bsec_get_state(0, serialized_state, n_serialized_state_max, work_buffer_state, n_work_buffer_size, &n_serialized_state);
+
+ \endcode
+ */
+
+bsec_library_return_t bsec_get_state(const uint8_t state_set_id, uint8_t * serialized_state,
+ const uint32_t n_serialized_state_max, uint8_t * work_buffer, const uint32_t n_work_buffer,
+ uint32_t * n_serialized_state);
+
+/*!
+ * @brief Retrieve BMExxx sensor instructions
+ *
+ * The bsec_sensor_control() interface is a key feature of BSEC, as it allows an easy way for the signal processing
+ * library to control the operation of the BME sensor. This is important since gas sensor behaviour is mainly
+ * determined by how the integrated heater is configured. To ensure an easy integration of BSEC into any system,
+ * bsec_sensor_control() will provide the caller with information about the current sensor configuration that is
+ * necessary to fulfill the input requirements derived from the current outputs requested via
+ * bsec_update_subscription().
+ *
+ * In practice the use of this function shall be as follows:
+ * - Call bsec_sensor_control() which returns a bsec_bme_settings_t struct.
+ * - Based on the information contained in this struct, the sensor is configured and a forced-mode measurement is
+ * triggered if requested by bsec_sensor_control().
+ * - Once this forced-mode measurement is complete, the signals specified in this struct shall be passed to
+ * bsec_do_steps() to perform the signal processing.
+ * - After processing, the process should sleep until the bsec_bme_settings_t::next_call timestamp is reached.
+ *
+ *
+ * @param [in] time_stamp Current timestamp in [ns]
+ * @param[out] sensor_settings Settings to be passed to API to operate sensor at this time instance
+ *
+ * @return Zero when successful, otherwise an error code
+ */
+
+bsec_library_return_t bsec_sensor_control(const int64_t time_stamp, bsec_bme_settings_t *sensor_settings);
+
+/*@}*/ //BSEC Interface
+
+#ifdef __cplusplus
+ }
+#endif
+
+#endif /* __BSEC_INTERFACE_H__ */
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_iaq.config
new file mode 100644
index 00000000..f6c7b918
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_iaq.csv
new file mode 100644
index 00000000..f4fb4d9e
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,30,235,0,0
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..da79cab0
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,30,235,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_300s_28d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_iaq.config
new file mode 100644
index 00000000..b0fff47a
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_iaq.csv
new file mode 100644
index 00000000..318c0691
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,195,255,0,0
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..85884b30
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,195,255,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_300s_4d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_iaq.config
new file mode 100644
index 00000000..3a2fcdf2
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_iaq.csv
new file mode 100644
index 00000000..9f8e21ea
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,140,226,0,0
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..a66a3478
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,140,226,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_3s_28d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_iaq.config
new file mode 100644
index 00000000..7bd1e535
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_iaq.csv
new file mode 100644
index 00000000..5eeae615
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,81,246,0,0
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..625cdc4e
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,7,240,150,61,0,0,0,0,0,0,0,0,28,124,225,61,52,128,215,63,0,0,160,64,0,0,0,0,0,0,0,0,205,204,12,62,103,213,39,62,230,63,76,192,0,0,0,0,0,0,0,0,145,237,60,191,251,58,64,63,177,80,131,64,0,0,0,0,0,0,0,0,93,254,227,62,54,60,133,191,0,0,64,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,81,246,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_18v_3s_4d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_iaq.config
new file mode 100644
index 00000000..e518942b
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_iaq.csv
new file mode 100644
index 00000000..480c841e
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,160,82,0,0
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..2f71de20
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,160,82,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_300s_28d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_iaq.config
new file mode 100644
index 00000000..698c69fe
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_iaq.csv
new file mode 100644
index 00000000..223adff0
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,125,70,0,0
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..f76832cc
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,48,117,0,0,0,0,125,70,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_300s_4d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_iaq.config
new file mode 100644
index 00000000..f2ff5189
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_iaq.csv
new file mode 100644
index 00000000..1396776c
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,50,91,0,0
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..e1f1bfe3
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,168,19,73,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,50,91,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_3s_28d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_iaq.config b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_iaq.config
new file mode 100644
index 00000000..a79b3ccb
Binary files /dev/null and b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_iaq.config differ
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_iaq.csv b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_iaq.csv
new file mode 100644
index 00000000..b0001d9c
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_iaq.csv
@@ -0,0 +1 @@
+454,1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,239,79,0,0
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_serialized_configurations_iaq.c b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_serialized_configurations_iaq.c
new file mode 100644
index 00000000..bce43cc3
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_serialized_configurations_iaq.c
@@ -0,0 +1,5 @@
+#include "bsec_serialized_configurations_iaq.h"
+
+const uint8_t bsec_config_iaq[454] =
+ {1,7,4,1,61,0,0,0,0,0,0,0,174,1,0,0,48,0,1,0,137,65,0,63,205,204,204,62,0,0,64,63,205,204,204,62,0,0,225,68,0,192,168,71,64,49,119,76,0,0,0,0,0,80,5,95,0,0,0,0,0,0,0,0,28,0,2,0,0,244,1,225,0,25,0,0,128,64,0,0,32,65,144,1,0,0,112,65,0,0,0,63,16,0,3,0,10,215,163,60,10,215,35,59,10,215,35,59,9,0,5,0,0,0,0,0,1,88,0,9,0,229,208,34,62,0,0,0,0,0,0,0,0,218,27,156,62,225,11,67,64,0,0,160,64,0,0,0,0,0,0,0,0,94,75,72,189,93,254,159,64,66,62,160,191,0,0,0,0,0,0,0,0,33,31,180,190,138,176,97,64,65,241,99,190,0,0,0,0,0,0,0,0,167,121,71,61,165,189,41,192,184,30,189,64,12,0,10,0,0,0,0,0,0,0,0,0,229,0,254,0,2,1,5,48,117,100,0,44,1,112,23,151,7,132,3,197,0,92,4,144,1,64,1,64,1,144,1,48,117,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,48,117,48,117,100,0,100,0,100,0,100,0,48,117,48,117,48,117,100,0,100,0,100,0,48,117,48,117,100,0,100,0,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,44,1,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,8,7,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,112,23,255,255,255,255,255,255,255,255,220,5,220,5,220,5,255,255,255,255,255,255,220,5,220,5,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,44,1,0,0,0,0,239,79,0,0};
+
diff --git a/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_serialized_configurations_iaq.h b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_serialized_configurations_iaq.h
new file mode 100644
index 00000000..1986e2be
--- /dev/null
+++ b/lib/Bosch-BSEC/config/generic_33v_3s_4d/bsec_serialized_configurations_iaq.h
@@ -0,0 +1,4 @@
+#include
+
+extern const uint8_t bsec_config_iaq[454];
+
diff --git a/lib/Bosch-BSEC/docs/BSEC - release notes_1.4.7.1.pdf b/lib/Bosch-BSEC/docs/BSEC - release notes_1.4.7.1.pdf
new file mode 100644
index 00000000..9d40e3c5
Binary files /dev/null and b/lib/Bosch-BSEC/docs/BSEC - release notes_1.4.7.1.pdf differ
diff --git a/lib/Bosch-BSEC/docs/BSEC_Binary_Size_Information.pdf b/lib/Bosch-BSEC/docs/BSEC_Binary_Size_Information.pdf
new file mode 100644
index 00000000..f6a62ed5
Binary files /dev/null and b/lib/Bosch-BSEC/docs/BSEC_Binary_Size_Information.pdf differ
diff --git a/lib/Bosch-BSEC/docs/BST-BME680-Integration-Guide-AN008-47.pdf b/lib/Bosch-BSEC/docs/BST-BME680-Integration-Guide-AN008-47.pdf
new file mode 100644
index 00000000..6eca6ff5
--- /dev/null
+++ b/lib/Bosch-BSEC/docs/BST-BME680-Integration-Guide-AN008-47.pdf
@@ -0,0 +1,17794 @@
+%PDF-1.7
+%
+4 0 obj
+<< /S /GoTo /D (chapter.1) >>
+endobj
+7 0 obj
+(\376\377\000B\000S\000E\000C\000\040\000I\000n\000t\000e\000g\000r\000a\000t\000i\000o\000n\000\040\000G\000u\000i\000d\000e\000l\000i\000n\000e)
+endobj
+8 0 obj
+<< /S /GoTo /D (section.1.1) >>
+endobj
+11 0 obj
+(\376\377\000O\000v\000e\000r\000v\000i\000e\000w\000\040\000o\000f\000\040\000B\000M\000E\000\040\000F\000a\000m\000i\000l\000y\000\040\000S\000e\000n\000s\000o\000r\000s)
+endobj
+12 0 obj
+<< /S /GoTo /D (section.1.2) >>
+endobj
+15 0 obj
+(\376\377\000T\000h\000e\000\040\000E\000n\000v\000i\000r\000o\000n\000m\000e\000n\000t\000a\000l\000\040\000F\000u\000s\000i\000o\000n\000\040\000L\000i\000b\000r\000a\000r\000y\000\040\000B\000S\000E\000C)
+endobj
+16 0 obj
+<< /S /GoTo /D (subsection.1.2.1) >>
+endobj
+19 0 obj
+(\376\377\000B\000S\000E\000C\000\040\000L\000i\000b\000r\000a\000r\000y\000\040\000S\000o\000l\000u\000t\000i\000o\000n\000s)
+endobj
+20 0 obj
+<< /S /GoTo /D (subsection.1.2.2) >>
+endobj
+23 0 obj
+(\376\377\000B\000S\000E\000C\000\040\000C\000o\000n\000f\000i\000g\000u\000r\000a\000t\000i\000o\000n\000\040\000S\000e\000t\000t\000i\000n\000g\000s)
+endobj
+24 0 obj
+<< /S /GoTo /D (subsection.1.2.3) >>
+endobj
+27 0 obj
+(\376\377\000K\000e\000y\000\040\000F\000e\000a\000t\000u\000r\000e\000s)
+endobj
+28 0 obj
+<< /S /GoTo /D (subsection.1.2.4) >>
+endobj
+31 0 obj
+(\376\377\000S\000u\000p\000p\000o\000r\000t\000e\000d\000\040\000V\000i\000r\000t\000u\000a\000l\000\040\000S\000e\000n\000s\000o\000r\000\040\000O\000u\000t\000p\000u\000t\000\040\000S\000i\000g\000n\000a\000l\000s)
+endobj
+32 0 obj
+<< /S /GoTo /D (section.1.3) >>
+endobj
+35 0 obj
+(\376\377\000R\000e\000q\000u\000i\000r\000e\000m\000e\000n\000t\000s\000\040\000f\000o\000r\000\040\000I\000n\000t\000e\000g\000r\000a\000t\000i\000o\000n)
+endobj
+36 0 obj
+<< /S /GoTo /D (subsection.1.3.1) >>
+endobj
+39 0 obj
+(\376\377\000H\000a\000r\000d\000w\000a\000r\000e)
+endobj
+40 0 obj
+<< /S /GoTo /D (subsection.1.3.2) >>
+endobj
+43 0 obj
+(\376\377\000S\000o\000f\000t\000w\000a\000r\000e\000\040\000F\000r\000a\000m\000e\000w\000o\000r\000k)
+endobj
+44 0 obj
+<< /S /GoTo /D (subsection.1.3.3) >>
+endobj
+47 0 obj
+(\376\377\000P\000h\000y\000s\000i\000c\000a\000l\000\040\000I\000n\000p\000u\000t\000\040\000S\000e\000n\000s\000o\000r\000\040\000S\000i\000g\000n\000a\000l\000s)
+endobj
+48 0 obj
+<< /S /GoTo /D (subsection.1.3.4) >>
+endobj
+51 0 obj
+(\376\377\000B\000u\000i\000l\000d\000\040\000t\000h\000e\000\040\000S\000o\000l\000u\000t\000i\000o\000n)
+endobj
+52 0 obj
+<< /S /GoTo /D (chapter.2) >>
+endobj
+55 0 obj
+(\376\377\000B\000S\000E\000C\000\040\000S\000t\000e\000p\000-\000b\000y\000-\000s\000t\000e\000p\000\040\000E\000x\000a\000m\000p\000l\000e)
+endobj
+56 0 obj
+<< /S /GoTo /D (section.2.1) >>
+endobj
+59 0 obj
+(\376\377\000P\000r\000e\000r\000e\000q\000u\000i\000s\000i\000t\000e\000s)
+endobj
+60 0 obj
+<< /S /GoTo /D (section.2.2) >>
+endobj
+63 0 obj
+(\376\377\000S\000e\000t\000t\000i\000n\000g\000\040\000E\000v\000e\000r\000y\000t\000h\000i\000n\000g\000\040\000U\000p)
+endobj
+64 0 obj
+<< /S /GoTo /D (section.2.3) >>
+endobj
+67 0 obj
+(\376\377\000T\000h\000e\000\040\000E\000x\000a\000m\000p\000l\000e\000\040\000C\000o\000d\000e)
+endobj
+68 0 obj
+<< /S /GoTo /D (section.2.4) >>
+endobj
+71 0 obj
+(\376\377\000H\000e\000l\000l\000o\000\040\000`\000\250\000I\000n\000d\000o\000o\000r\000-\000A\000i\000r\000-\000Q\000u\000a\000l\000i\000t\000y\000`\000\250)
+endobj
+72 0 obj
+<< /S /GoTo /D (section.2.5) >>
+endobj
+75 0 obj
+(\376\377\000R\000e\000d\000u\000c\000i\000n\000g\000\040\000p\000o\000w\000e\000r\000\040\000c\000o\000n\000s\000u\000m\000p\000t\000i\000o\000n)
+endobj
+76 0 obj
+<< /S /GoTo /D (section.2.6) >>
+endobj
+79 0 obj
+(\376\377\000T\000r\000i\000g\000g\000e\000r\000\040\000U\000L\000P\000\040\000p\000l\000u\000s)
+endobj
+80 0 obj
+<< /S /GoTo /D (section.2.7) >>
+endobj
+83 0 obj
+(\376\377\000T\000e\000m\000p\000e\000r\000a\000t\000u\000r\000e\000\040\000o\000f\000f\000s\000e\000t\000s\000\040\000d\000u\000e\000\040\000t\000o\000\040\000h\000e\000a\000t\000\040\000s\000o\000u\000r\000c\000e\000s\000\040\000o\000n\000\040\000t\000h\000e\000\040\000b\000o\000a\000r\000d)
+endobj
+84 0 obj
+<< /S /GoTo /D (section.2.8) >>
+endobj
+87 0 obj
+(\376\377\000S\000i\000m\000u\000l\000a\000t\000e\000\040\000m\000u\000l\000t\000i\000p\000l\000e\000\040\000s\000e\000n\000s\000o\000r\000s\000\040\000u\000s\000i\000n\000g\000\040\000s\000i\000n\000g\000l\000e\000\040\000B\000S\000E\000C\000\040\000i\000n\000s\000t\000a\000n\000c\000e)
+endobj
+88 0 obj
+<< /S /GoTo /D (section.2.9) >>
+endobj
+91 0 obj
+(\376\377\000C\000o\000n\000c\000l\000u\000s\000i\000o\000n)
+endobj
+92 0 obj
+<< /S /GoTo /D (chapter.3) >>
+endobj
+95 0 obj
+(\376\377\000F\000A\000Q)
+endobj
+96 0 obj
+<< /S /GoTo /D (section.3.1) >>
+endobj
+99 0 obj
+(\376\377\000N\000o\000\040\000O\000u\000t\000p\000u\000t\000\040\000F\000r\000o\000m\000\040\000b\000s\000e\000c\000\137\000d\000o\000\137\000s\000t\000e\000p\000s\000\050\000\051)
+endobj
+100 0 obj
+<< /S /GoTo /D (section.3.2) >>
+endobj
+103 0 obj
+(\376\377\000I\000A\000Q\000\040\000o\000u\000t\000p\000u\000t\000\040\000d\000o\000e\000s\000\040\000n\000o\000t\000\040\000c\000h\000a\000n\000g\000e\000\040\000o\000r\000\040\000a\000c\000c\000u\000r\000a\000c\000y\000\040\000r\000e\000m\000a\000i\000n\000s\000\040\0000)
+endobj
+104 0 obj
+<< /S /GoTo /D (section.3.3) >>
+endobj
+107 0 obj
+(\376\377\000E\000r\000r\000o\000r\000\040\000C\000o\000d\000e\000s\000\040\000a\000n\000d\000\040\000C\000o\000r\000r\000e\000c\000t\000i\000v\000e\000\040\000M\000e\000a\000s\000u\000r\000e\000s)
+endobj
+108 0 obj
+<< /S /GoTo /D (subsection.3.3.1) >>
+endobj
+111 0 obj
+(\376\377\000E\000r\000r\000o\000r\000s\000\040\000R\000e\000t\000u\000r\000n\000e\000d\000\040\000b\000y\000\040\000b\000s\000e\000c\000\137\000d\000o\000\137\000s\000t\000e\000p\000s\000\050\000\051)
+endobj
+112 0 obj
+<< /S /GoTo /D (subsection.3.3.2) >>
+endobj
+115 0 obj
+(\376\377\000E\000r\000r\000o\000r\000s\000\040\000R\000e\000t\000u\000r\000n\000e\000d\000\040\000b\000y\000\040\000b\000s\000e\000c\000\137\000u\000p\000d\000a\000t\000e\000\137\000s\000u\000b\000s\000c\000r\000i\000p\000t\000i\000o\000n\000\050\000\051)
+endobj
+116 0 obj
+<< /S /GoTo /D (subsection.3.3.3) >>
+endobj
+119 0 obj
+(\376\377\000E\000r\000r\000o\000r\000s\000\040\000R\000e\000t\000u\000r\000n\000e\000d\000\040\000b\000y\000\040\000b\000s\000e\000c\000\137\000s\000e\000t\000\137\000c\000o\000n\000f\000i\000g\000u\000r\000a\000t\000i\000o\000n\000\050\000\051\000\040\000/\000\040\000b\000s\000e\000c\000\137\000s\000e\000t\000\137\000s\000t\000a\000t\000e\000\050\000\051)
+endobj
+120 0 obj
+<< /S /GoTo /D (subsection.3.3.4) >>
+endobj
+123 0 obj
+(\376\377\000E\000r\000r\000o\000r\000s\000\040\000R\000e\000t\000u\000r\000n\000e\000d\000\040\000b\000y\000\040\000b\000s\000e\000c\000\137\000s\000e\000n\000s\000o\000r\000\137\000c\000o\000n\000t\000r\000o\000l\000\050\000\051)
+endobj
+124 0 obj
+<< /S /GoTo /D (chapter.4) >>
+endobj
+127 0 obj
+(\376\377\000M\000o\000d\000u\000l\000e\000\040\000D\000o\000c\000u\000m\000e\000n\000t\000a\000t\000i\000o\000n)
+endobj
+128 0 obj
+<< /S /GoTo /D (section.4.1) >>
+endobj
+131 0 obj
+(\376\377\000B\000S\000E\000C\000\040\000C\000\040\000I\000n\000t\000e\000r\000f\000a\000c\000e)
+endobj
+132 0 obj
+<< /S /GoTo /D (subsection.4.1.1) >>
+endobj
+135 0 obj
+(\376\377\000I\000n\000t\000e\000r\000f\000a\000c\000e\000\040\000U\000s\000a\000g\000e)
+endobj
+136 0 obj
+<< /S /GoTo /D (subsection.4.1.2) >>
+endobj
+139 0 obj
+(\376\377\000I\000n\000t\000e\000r\000f\000a\000c\000e\000\040\000F\000u\000n\000c\000t\000i\000o\000n\000s)
+endobj
+140 0 obj
+<< /S /GoTo /D (subsection.4.1.3) >>
+endobj
+143 0 obj
+(\376\377\000E\000n\000u\000m\000e\000r\000a\000t\000i\000o\000n\000s)
+endobj
+144 0 obj
+<< /S /GoTo /D (subsection.4.1.4) >>
+endobj
+147 0 obj
+(\376\377\000D\000e\000f\000i\000n\000e\000s)
+endobj
+148 0 obj
+<< /S /GoTo /D (chapter.5) >>
+endobj
+151 0 obj
+(\376\377\000D\000a\000t\000a\000\040\000S\000t\000r\000u\000c\000t\000u\000r\000e\000\040\000D\000o\000c\000u\000m\000e\000n\000t\000a\000t\000i\000o\000n)
+endobj
+152 0 obj
+<< /S /GoTo /D (section.5.1) >>
+endobj
+155 0 obj
+(\376\377\000b\000s\000e\000c\000\137\000b\000m\000e\000\137\000s\000e\000t\000t\000i\000n\000g\000s\000\137\000t\000\040\000S\000t\000r\000u\000c\000t\000\040\000R\000e\000f\000e\000r\000e\000n\000c\000e)
+endobj
+156 0 obj
+<< /S /GoTo /D (subsection.5.1.1) >>
+endobj
+159 0 obj
+(\376\377\000D\000e\000t\000a\000i\000l\000e\000d\000\040\000D\000e\000s\000c\000r\000i\000p\000t\000i\000o\000n)
+endobj
+160 0 obj
+<< /S /GoTo /D (subsection.5.1.2) >>
+endobj
+163 0 obj
+(\376\377\000F\000i\000e\000l\000d\000\040\000D\000o\000c\000u\000m\000e\000n\000t\000a\000t\000i\000o\000n)
+endobj
+164 0 obj
+<< /S /GoTo /D (section.5.2) >>
+endobj
+167 0 obj
+(\376\377\000b\000s\000e\000c\000\137\000i\000n\000p\000u\000t\000\137\000t\000\040\000S\000t\000r\000u\000c\000t\000\040\000R\000e\000f\000e\000r\000e\000n\000c\000e)
+endobj
+168 0 obj
+<< /S /GoTo /D (subsection.5.2.1) >>
+endobj
+171 0 obj
+(\376\377\000D\000e\000t\000a\000i\000l\000e\000d\000\040\000D\000e\000s\000c\000r\000i\000p\000t\000i\000o\000n)
+endobj
+172 0 obj
+<< /S /GoTo /D (subsection.5.2.2) >>
+endobj
+175 0 obj
+(\376\377\000F\000i\000e\000l\000d\000\040\000D\000o\000c\000u\000m\000e\000n\000t\000a\000t\000i\000o\000n)
+endobj
+176 0 obj
+<< /S /GoTo /D (section.5.3) >>
+endobj
+179 0 obj
+(\376\377\000b\000s\000e\000c\000\137\000o\000u\000t\000p\000u\000t\000\137\000t\000\040\000S\000t\000r\000u\000c\000t\000\040\000R\000e\000f\000e\000r\000e\000n\000c\000e)
+endobj
+180 0 obj
+<< /S /GoTo /D (subsection.5.3.1) >>
+endobj
+183 0 obj
+(\376\377\000D\000e\000t\000a\000i\000l\000e\000d\000\040\000D\000e\000s\000c\000r\000i\000p\000t\000i\000o\000n)
+endobj
+184 0 obj
+<< /S /GoTo /D (subsection.5.3.2) >>
+endobj
+187 0 obj
+(\376\377\000F\000i\000e\000l\000d\000\040\000D\000o\000c\000u\000m\000e\000n\000t\000a\000t\000i\000o\000n)
+endobj
+188 0 obj
+<< /S /GoTo /D (section.5.4) >>
+endobj
+191 0 obj
+(\376\377\000b\000s\000e\000c\000\137\000s\000e\000n\000s\000o\000r\000\137\000c\000o\000n\000f\000i\000g\000u\000r\000a\000t\000i\000o\000n\000\137\000t\000\040\000S\000t\000r\000u\000c\000t\000\040\000R\000e\000f\000e\000r\000e\000n\000c\000e)
+endobj
+192 0 obj
+<< /S /GoTo /D (subsection.5.4.1) >>
+endobj
+195 0 obj
+(\376\377\000D\000e\000t\000a\000i\000l\000e\000d\000\040\000D\000e\000s\000c\000r\000i\000p\000t\000i\000o\000n)
+endobj
+196 0 obj
+<< /S /GoTo /D (subsection.5.4.2) >>
+endobj
+199 0 obj
+(\376\377\000F\000i\000e\000l\000d\000\040\000D\000o\000c\000u\000m\000e\000n\000t\000a\000t\000i\000o\000n)
+endobj
+200 0 obj
+<< /S /GoTo /D (section.5.5) >>
+endobj
+203 0 obj
+(\376\377\000b\000s\000e\000c\000\137\000v\000e\000r\000s\000i\000o\000n\000\137\000t\000\040\000S\000t\000r\000u\000c\000t\000\040\000R\000e\000f\000e\000r\000e\000n\000c\000e)
+endobj
+204 0 obj
+<< /S /GoTo /D (subsection.5.5.1) >>
+endobj
+207 0 obj
+(\376\377\000D\000e\000t\000a\000i\000l\000e\000d\000\040\000D\000e\000s\000c\000r\000i\000p\000t\000i\000o\000n)
+endobj
+208 0 obj
+<< /S /GoTo /D (subsection.5.5.2) >>
+endobj
+211 0 obj
+(\376\377\000F\000i\000e\000l\000d\000\040\000D\000o\000c\000u\000m\000e\000n\000t\000a\000t\000i\000o\000n)
+endobj
+212 0 obj
+<< /S /GoTo /D [213 0 R /Fit] >>
+endobj
+224 0 obj <<
+/Length 855
+/Filter /FlateDecode
+>>
+stream
+xڭUKo8WQJQ"VYhƾ=(mk!KIw(J:H-`{D|FGf`G{o٧gaƤ9'(j8%h6oc#|A4
wyL=
+zBS.#5LkeZJM43 +
(c"!Po)95 "`ah5Ă(:lNڼ*D:Xvyf_h)\TMUieyUeM53Sl|8Vrp
X13_
p,zr_)~=
+bjb'tH$־,̘H{B߰6ٜ(߽xW76mLwI]
e=vUck07kNdj=W* fd2,cY" Ӯ0Pۤr ULB+ϡi7Fcٜ`\Lc&
#y"{'`d7{F+l
+ܻƍ'N8u
)ȉG9CT}?vsU_9#qPქN=>D"PKql~~Hd٠OA|5ŠJZa^Iໄa0?^˒`e˦[rM$