├── .gitignore ├── components ├── bme680 │ ├── component.mk │ ├── bme680_platform.c │ ├── bme680_platform.h │ ├── bme680_types.h │ ├── bme680.h │ └── bme680.c └── esp8266_wrapper │ ├── component.mk │ ├── esp8266_wrapper.h │ └── esp8266_wrapper.c ├── main ├── component.mk └── bme680_example.c ├── Makefile ├── LICENSE └── README.md /.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | *# 3 | .#* 4 | *.swp 5 | *.o 6 | 7 | sdkconfig 8 | build 9 | 10 | -------------------------------------------------------------------------------- /components/bme680/component.mk: -------------------------------------------------------------------------------- 1 | # 2 | # Component makefile. 3 | # 4 | COMPONENT_ADD_INCLUDEDIRS := . 5 | -------------------------------------------------------------------------------- /main/component.mk: -------------------------------------------------------------------------------- 1 | # 2 | # Main Makefile. This is basically the same as a component makefile. 3 | # 4 | -------------------------------------------------------------------------------- /components/esp8266_wrapper/component.mk: -------------------------------------------------------------------------------- 1 | # 2 | # Component makefile. 3 | # 4 | COMPONENT_ADD_INCLUDEDIRS := . 5 | -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- 1 | # 2 | # This is a project Makefile. It is assumed the directory this Makefile resides in is a 3 | # project subdirectory. 4 | # 5 | 6 | PROJECT_NAME := bme680 7 | 8 | include $(IDF_PATH)/make/project.mk 9 | 10 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2022, Gunar Schorcht 4 | 5 | Redistribution and use in source and binary forms, with or without 6 | modification, are permitted provided that the following conditions are met: 7 | 8 | 1. Redistributions of source code must retain the above copyright notice, this 9 | list of conditions and the following disclaimer. 10 | 11 | 2. Redistributions in binary form must reproduce the above copyright notice, 12 | this list of conditions and the following disclaimer in the documentation 13 | and/or other materials provided with the distribution. 14 | 15 | 3. Neither the name of the copyright holder nor the names of its 16 | contributors may be used to endorse or promote products derived from 17 | this software without specific prior written permission. 18 | 19 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 20 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 21 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 22 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 23 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 24 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 25 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 26 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 27 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 28 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 29 | -------------------------------------------------------------------------------- /components/bme680/bme680_platform.c: -------------------------------------------------------------------------------- 1 | /* 2 | * Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure 3 | * and gas sensor connected to I2C or SPI 4 | * 5 | * This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos) 6 | * [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32 7 | * and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux 8 | * based systems using a wrapper library for ESP8266 functions. 9 | * 10 | * --------------------------------------------------------------------------- 11 | * 12 | * The BSD License (3-clause license) 13 | * 14 | * Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht) 15 | * All rights reserved. 16 | * 17 | * Redistribution and use in source and binary forms, with or without 18 | * modification, are permitted provided that the following conditions are met: 19 | * 20 | * 1. Redistributions of source code must retain the above copyright notice, 21 | * this list of conditions and the following disclaimer. 22 | * 23 | * 2. Redistributions in binary form must reproduce the above copyright 24 | * notice, this list of conditions and the following disclaimer in the 25 | * documentation and/or other materials provided with the distribution. 26 | * 27 | * 3. Neither the name of the copyright holder nor the names of its 28 | * contributors may be used to endorse or promote products derived from this 29 | * software without specific prior written permission. 30 | * 31 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 32 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 33 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 34 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 35 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 36 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 37 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 38 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 39 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 40 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 41 | * POSSIBILITY OF SUCH DAMAGE. 42 | * 43 | * The information provided is believed to be accurate and reliable. The 44 | * copyright holder assumes no responsibility for the consequences of use 45 | * of such information nor for any infringement of patents or other rights 46 | * of third parties which may result from its use. No license is granted by 47 | * implication or otherwise under any patent or patent rights of the copyright 48 | * holder. 49 | */ 50 | 51 | // platform specific defines, includes and functions 52 | 53 | #include "bme680_platform.h" 54 | 55 | SemaphoreHandle_t spi_sem = 0; 56 | 57 | -------------------------------------------------------------------------------- /components/bme680/bme680_platform.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure 3 | * and gas sensor connected to I2C or SPI 4 | * 5 | * This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos) 6 | * [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32 7 | * and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux 8 | * based systems using a wrapper library for ESP8266 functions. 9 | * 10 | * --------------------------------------------------------------------------- 11 | * 12 | * The BSD License (3-clause license) 13 | * 14 | * Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht) 15 | * All rights reserved. 16 | * 17 | * Redistribution and use in source and binary forms, with or without 18 | * modification, are permitted provided that the following conditions are met: 19 | * 20 | * 1. Redistributions of source code must retain the above copyright notice, 21 | * this list of conditions and the following disclaimer. 22 | * 23 | * 2. Redistributions in binary form must reproduce the above copyright 24 | * notice, this list of conditions and the following disclaimer in the 25 | * documentation and/or other materials provided with the distribution. 26 | * 27 | * 3. Neither the name of the copyright holder nor the names of its 28 | * contributors may be used to endorse or promote products derived from this 29 | * software without specific prior written permission. 30 | * 31 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 32 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 33 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 34 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 35 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 36 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 37 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 38 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 39 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 40 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 41 | * POSSIBILITY OF SUCH DAMAGE. 42 | * 43 | * The information provided is believed to be accurate and reliable. The 44 | * copyright holder assumes no responsibility for the consequences of use 45 | * of such information nor for any infringement of patents or other rights 46 | * of third parties which may result from its use. No license is granted by 47 | * implication or otherwise under any patent or patent rights of the copyright 48 | * holder. 49 | */ 50 | 51 | /** 52 | * Platform file: platform specific definitions, includes and functions 53 | */ 54 | 55 | #ifndef __BME680_PLATFORM_H__ 56 | #define __BME680_PLATFORM_H__ 57 | 58 | #ifdef ESP_PLATFORM // ESP32 (ESP-IDF) 59 | 60 | // platform specific includes 61 | #include "esp8266_wrapper.h" 62 | #include 63 | 64 | #endif // ESP_PLATFORM 65 | 66 | #endif // __BME680_PLATFORM_H__ 67 | -------------------------------------------------------------------------------- /components/esp8266_wrapper/esp8266_wrapper.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Wrapper module for source code compatibility with esp-open-rtos. 3 | */ 4 | 5 | #ifndef __ESP8266_WRAPPER_H__ 6 | #define __ESP8266_WRAPPER_H__ 7 | 8 | #ifdef ESP_PLATFORM // ESP32 (ESP-IDF) 9 | 10 | #ifdef __cplusplus 11 | extern "C" { 12 | #endif 13 | 14 | #include "freertos/FreeRTOS.h" 15 | #include "freertos/task.h" 16 | #include "freertos/queue.h" 17 | 18 | #include "driver/uart.h" 19 | #include "driver/spi_common.h" 20 | 21 | /* 22 | * esp-open-rtos SDK function wrapper 23 | */ 24 | 25 | uint32_t sdk_system_get_time (); 26 | 27 | #define user_init app_main 28 | #define uart_set_baud(p,r) uart_set_baudrate (p,r) 29 | 30 | #ifdef CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION 31 | #define vTaskDelayUntil(t,d) { *t=*t; vTaskDelay(d); } 32 | #endif 33 | 34 | #define IRAM IRAM_ATTR 35 | 36 | #define GPIO_INTTYPE_NONE GPIO_INTR_DISABLE 37 | #define GPIO_INTTYPE_EDGE_POS GPIO_INTR_POSEDGE 38 | #define GPIO_INTTYPE_EDGE_NEG GPIO_INTR_NEGEDGE 39 | #define GPIO_INTTYPE_EDGE_ANY GPIO_INTR_ANYEDGE 40 | #define GPIO_INTTYPE_LEVEL_LOW GPIO_INTR_LOW_LEVEL 41 | #define GPIO_INTTYPE_LEVEL_HIGH GPIO_INTR_HIGH_LEVEL 42 | 43 | // Set it true, if isr_service is already installed anywhere else or should 44 | // not be installed, otherwise, *gpio_set_interrupt* install it when it is 45 | // called first time. 46 | extern bool gpio_isr_service_installed; 47 | 48 | // pull-up, pull-down configuration used for next call of *gpio_set_interrupt* 49 | extern bool auto_pull_up; // default false; 50 | extern bool auto_pull_down; // default true; 51 | 52 | // ISR handler type compatible to the ESP8266 53 | typedef void (*gpio_interrupt_handler_t)(uint8_t gpio); 54 | 55 | // GPIO set interrupt function compatible to ESP8266 56 | esp_err_t gpio_set_interrupt(gpio_num_t gpio, 57 | gpio_int_type_t type, 58 | gpio_interrupt_handler_t handler); 59 | 60 | // GPIO enable function compatible to esp-open-rtos 61 | #define GPIO_INPUT GPIO_MODE_INPUT 62 | #define GPIO_OUTPUT GPIO_MODE_OUTPUT 63 | #define GPIO_OUT_OPEN_DRAIN GPIO_MODE_OUTPUT_OD 64 | 65 | void gpio_enable (gpio_num_t gpio, const gpio_mode_t mode); 66 | 67 | /* 68 | * esp-open-rtos I2C interface wrapper 69 | */ 70 | 71 | #define I2C_FREQ_80K 80000 72 | #define I2C_FREQ_100K 100000 73 | #define I2C_FREQ_400K 400000 74 | #define I2C_FREQ_500K 500000 75 | #define I2C_FREQ_600K 600000 76 | #define I2C_FREQ_800K 800000 77 | #define I2C_FREQ_1000K 1000000 78 | #define I2C_FREQ_1300K 1300000 79 | 80 | #define i2c_set_clock_stretch(bus,cs) // not needed on ESP32 81 | 82 | void i2c_init (int bus, gpio_num_t scl, gpio_num_t sda, uint32_t freq); 83 | 84 | int i2c_slave_write (uint8_t bus, uint8_t addr, const uint8_t *reg, 85 | uint8_t *data, uint32_t len); 86 | 87 | int i2c_slave_read (uint8_t bus, uint8_t addr, const uint8_t *reg, 88 | uint8_t *data, uint32_t len); 89 | 90 | /* 91 | * esp-open-rtos SPI interface wrapper 92 | */ 93 | 94 | bool spi_bus_init (spi_host_device_t host, 95 | uint8_t sclk , uint8_t miso, uint8_t mosi); 96 | 97 | bool spi_device_init (uint8_t bus, uint8_t cs); 98 | 99 | size_t spi_transfer_pf(uint8_t bus, uint8_t cs, 100 | const uint8_t *mosi, uint8_t *miso, uint16_t len); 101 | 102 | /* 103 | * freertos api wrapper 104 | */ 105 | 106 | #define QueueHandle_t xQueueHandle 107 | 108 | #ifdef __cplusplus 109 | } 110 | #endif 111 | 112 | #endif // ESP_PLATFORM 113 | 114 | #endif // __ESP8266_WRAPPER_H__ 115 | -------------------------------------------------------------------------------- /main/bme680_example.c: -------------------------------------------------------------------------------- 1 | /** 2 | * Simple example with one sensor connected either to I2C bus 0 or 3 | * SPI bus 1. 4 | * 5 | * Harware configuration: 6 | * 7 | * I2C 8 | * 9 | * +-----------------+ +----------+ 10 | * | ESP8266 / ESP32 | | BME680 | 11 | * | | | | 12 | * | GPIO 14 (SCL) ----> SCL | 13 | * | GPIO 13 (SDA) <---> SDA | 14 | * +-----------------+ +----------+ 15 | * 16 | * SPI 17 | * 18 | * +-----------------+ +----------+ +-----------------+ +----------+ 19 | * | ESP8266 | | BME680 | | ESP32 | | BME680 | 20 | * | | | | | | | | 21 | * | GPIO 14 (SCK) ----> SCK | | GPIO 16 (SCK) ----> SCK | 22 | * | GPIO 13 (MOSI)----> SDI | | GPIO 17 (MOSI)----> SDI | 23 | * | GPIO 12 (MISO)<---- SDO | | GPIO 18 (MISO)<---- SDO | 24 | * | GPIO 2 (CS) ----> CS | | GPIO 19 (CS) ----> CS | 25 | * +-----------------+ +---------+ +-----------------+ +----------+ 26 | */ 27 | 28 | /* -- use following constants to define the example mode ----------- */ 29 | 30 | // #define SPI_USED 31 | 32 | /* -- includes ----------------------------------------------------- */ 33 | 34 | #include "bme680.h" 35 | 36 | /* -- platform dependent definitions ------------------------------- */ 37 | 38 | #ifdef ESP_PLATFORM // ESP32 (ESP-IDF) 39 | 40 | // user task stack depth for ESP32 41 | #define TASK_STACK_DEPTH 2048 42 | 43 | // SPI interface definitions for ESP32 44 | #define SPI_BUS HSPI_HOST 45 | #define SPI_SCK_GPIO 16 46 | #define SPI_MOSI_GPIO 17 47 | #define SPI_MISO_GPIO 18 48 | #define SPI_CS_GPIO 19 49 | 50 | #else // ESP8266 (esp-open-rtos) 51 | 52 | // user task stack depth for ESP8266 53 | #define TASK_STACK_DEPTH 256 54 | 55 | // SPI interface definitions for ESP8266 56 | #define SPI_BUS 1 57 | #define SPI_SCK_GPIO 14 58 | #define SPI_MOSI_GPIO 13 59 | #define SPI_MISO_GPIO 12 60 | #define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used 61 | 62 | #endif // ESP_PLATFORM 63 | 64 | // I2C interface defintions for ESP32 and ESP8266 65 | #define I2C_BUS 0 66 | #define I2C_SCL_PIN 14 67 | #define I2C_SDA_PIN 13 68 | #define I2C_FREQ I2C_FREQ_100K 69 | 70 | /* -- user tasks --------------------------------------------------- */ 71 | 72 | static bme680_sensor_t* sensor = 0; 73 | 74 | /* 75 | * User task that triggers measurements of sensor every seconds. It uses 76 | * function *vTaskDelay* to wait for measurement results. Busy wating 77 | * alternative is shown in comments 78 | */ 79 | void user_task(void *pvParameters) 80 | { 81 | bme680_values_float_t values; 82 | 83 | TickType_t last_wakeup = xTaskGetTickCount(); 84 | 85 | // as long as sensor configuration isn't changed, duration is constant 86 | uint32_t duration = bme680_get_measurement_duration(sensor); 87 | 88 | while (1) 89 | { 90 | // trigger the sensor to start one TPHG measurement cycle 91 | if (bme680_force_measurement (sensor)) 92 | { 93 | // passive waiting until measurement results are available 94 | vTaskDelay (duration); 95 | 96 | // alternatively: busy waiting until measurement results are available 97 | // while (bme680_is_measuring (sensor)) ; 98 | 99 | // get the results and do something with them 100 | if (bme680_get_results_float (sensor, &values)) 101 | printf("%.3f BME680 Sensor: %.2f °C, %.2f %%, %.2f hPa, %.2f Ohm\n", 102 | (double)sdk_system_get_time()*1e-3, 103 | values.temperature, values.humidity, 104 | values.pressure, values.gas_resistance); 105 | } 106 | // passive waiting until 1 second is over 107 | vTaskDelayUntil(&last_wakeup, 1000 / portTICK_PERIOD_MS); 108 | } 109 | } 110 | 111 | /* -- main program ------------------------------------------------- */ 112 | 113 | void user_init(void) 114 | { 115 | // Set UART Parameter. 116 | uart_set_baud(0, 115200); 117 | // Give the UART some time to settle 118 | vTaskDelay(1); 119 | 120 | /** -- MANDATORY PART -- */ 121 | 122 | #ifdef SPI_USED 123 | 124 | spi_bus_init (SPI_BUS, SPI_SCK_GPIO, SPI_MISO_GPIO, SPI_MOSI_GPIO); 125 | 126 | // init the sensor connected to SPI_BUS with SPI_CS_GPIO as chip select. 127 | sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO); 128 | 129 | #else // I2C 130 | 131 | // Init all I2C bus interfaces at which BME680 sensors are connected 132 | i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ); 133 | 134 | // init the sensor with slave address BME680_I2C_ADDRESS_2 connected to I2C_BUS. 135 | sensor = bme680_init_sensor (I2C_BUS, BME680_I2C_ADDRESS_2, 0); 136 | 137 | #endif // SPI_USED 138 | 139 | if (sensor) 140 | { 141 | /** -- SENSOR CONFIGURATION PART (optional) --- */ 142 | 143 | // Changes the oversampling rates to 4x oversampling for temperature 144 | // and 2x oversampling for humidity. Pressure measurement is skipped. 145 | bme680_set_oversampling_rates(sensor, osr_4x, osr_none, osr_2x); 146 | 147 | // Change the IIR filter size for temperature and pressure to 7. 148 | bme680_set_filter_size(sensor, iir_size_7); 149 | 150 | // Change the heater profile 0 to 200 degree Celcius for 100 ms. 151 | bme680_set_heater_profile (sensor, 0, 200, 100); 152 | bme680_use_heater_profile (sensor, 0); 153 | 154 | // Set ambient temperature to 10 degree Celsius 155 | bme680_set_ambient_temperature (sensor, 10); 156 | 157 | /** -- TASK CREATION PART --- */ 158 | 159 | // must be done last to avoid concurrency situations with the sensor 160 | // configuration part 161 | 162 | // Create a task that uses the sensor 163 | xTaskCreate(user_task, "user_task", TASK_STACK_DEPTH, NULL, 2, NULL); 164 | } 165 | else 166 | printf("Could not initialize BME680 sensor\n"); 167 | } 168 | -------------------------------------------------------------------------------- /components/esp8266_wrapper/esp8266_wrapper.c: -------------------------------------------------------------------------------- 1 | /** 2 | * Wrapper module for source code compatibility with esp-open-rtos. 3 | */ 4 | 5 | #ifdef ESP_PLATFORM // ESP32 (ESP-IDF) 6 | 7 | #include 8 | #include 9 | 10 | #include "driver/spi_master.h" 11 | #include "driver/spi_common.h" 12 | 13 | #include "driver/i2c.h" 14 | #include "driver/gpio.h" 15 | 16 | #include "esp8266_wrapper.h" 17 | 18 | // esp-open-rtos SDK function wrapper 19 | 20 | uint32_t sdk_system_get_time () 21 | { 22 | struct timeval time; 23 | gettimeofday(&time,0); 24 | return time.tv_sec*1e6 + time.tv_usec; 25 | } 26 | 27 | bool gpio_isr_service_installed = false; 28 | bool auto_pull_up = false; 29 | bool auto_pull_down = true; 30 | 31 | esp_err_t gpio_set_interrupt(gpio_num_t gpio, 32 | gpio_int_type_t type, 33 | gpio_interrupt_handler_t handler) 34 | { 35 | if (!gpio_isr_service_installed) 36 | gpio_isr_service_installed = (gpio_install_isr_service(0) == ESP_OK); 37 | 38 | gpio_config_t gpio_cfg = { 39 | .pin_bit_mask = ((uint64_t)(((uint64_t)1)<< gpio)), 40 | .mode = GPIO_MODE_INPUT, 41 | .pull_up_en = auto_pull_up, 42 | .pull_down_en = auto_pull_down, 43 | .intr_type = type 44 | }; 45 | gpio_config(&gpio_cfg); 46 | 47 | // set interrupt handler 48 | gpio_isr_handler_add(gpio, (gpio_isr_t)handler, (void*)gpio); 49 | 50 | return ESP_OK; 51 | } 52 | 53 | void gpio_enable (gpio_num_t gpio, const gpio_mode_t mode) 54 | { 55 | gpio_config_t gpio_cfg = { 56 | .pin_bit_mask = ((uint64_t)(((uint64_t)1)<< gpio)), 57 | .mode = mode, 58 | .pull_up_en = auto_pull_up, 59 | .pull_down_en = auto_pull_down, 60 | }; 61 | gpio_config(&gpio_cfg); 62 | } 63 | 64 | // esp-open-rtos I2C interface wrapper 65 | 66 | #define I2C_ACK_VAL 0x0 67 | #define I2C_NACK_VAL 0x1 68 | 69 | void i2c_init (int bus, gpio_num_t scl, gpio_num_t sda, uint32_t freq) 70 | { 71 | i2c_config_t conf; 72 | conf.mode = I2C_MODE_MASTER; 73 | conf.sda_io_num = sda; 74 | conf.scl_io_num = scl; 75 | conf.sda_pullup_en = GPIO_PULLUP_ENABLE; 76 | conf.scl_pullup_en = GPIO_PULLUP_ENABLE; 77 | conf.master.clk_speed = freq; 78 | i2c_param_config(bus, &conf); 79 | i2c_driver_install(bus, I2C_MODE_MASTER, 0, 0, 0); 80 | } 81 | 82 | int i2c_slave_write (uint8_t bus, uint8_t addr, const uint8_t *reg, 83 | uint8_t *data, uint32_t len) 84 | { 85 | i2c_cmd_handle_t cmd = i2c_cmd_link_create(); 86 | i2c_master_start(cmd); 87 | i2c_master_write_byte(cmd, addr << 1 | I2C_MASTER_WRITE, true); 88 | if (reg) 89 | i2c_master_write_byte(cmd, *reg, true); 90 | if (data) 91 | i2c_master_write(cmd, data, len, true); 92 | i2c_master_stop(cmd); 93 | esp_err_t err = i2c_master_cmd_begin(bus, cmd, 1000 / portTICK_RATE_MS); 94 | i2c_cmd_link_delete(cmd); 95 | 96 | return err; 97 | } 98 | 99 | int i2c_slave_read (uint8_t bus, uint8_t addr, const uint8_t *reg, 100 | uint8_t *data, uint32_t len) 101 | { 102 | if (len == 0) return true; 103 | 104 | i2c_cmd_handle_t cmd = i2c_cmd_link_create(); 105 | if (reg) 106 | { 107 | i2c_master_start(cmd); 108 | i2c_master_write_byte(cmd, ( addr << 1 ) | I2C_MASTER_WRITE, true); 109 | i2c_master_write_byte(cmd, *reg, true); 110 | if (!data) 111 | i2c_master_stop(cmd); 112 | } 113 | if (data) 114 | { 115 | i2c_master_start(cmd); 116 | i2c_master_write_byte(cmd, ( addr << 1 ) | I2C_MASTER_READ, true); 117 | if (len > 1) i2c_master_read(cmd, data, len-1, I2C_ACK_VAL); 118 | i2c_master_read_byte(cmd, data + len-1, I2C_NACK_VAL); 119 | i2c_master_stop(cmd); 120 | } 121 | esp_err_t err = i2c_master_cmd_begin(bus, cmd, 1000 / portTICK_RATE_MS); 122 | i2c_cmd_link_delete(cmd); 123 | 124 | return err; 125 | } 126 | 127 | // esp-open-rtos SPI interface wrapper 128 | 129 | #define SPI_MAX_BUS 3 // ESP32 features three SPIs (SPI_HOST, HSPI_HOST and VSPI_HOST) 130 | #define SPI_MAX_CS 34 // GPIO 33 is the last port that can be used as output 131 | 132 | spi_device_handle_t spi_handles[SPI_MAX_CS] = { 0 }; 133 | 134 | bool spi_bus_init (spi_host_device_t host, uint8_t sclk , uint8_t miso, uint8_t mosi) 135 | { 136 | spi_bus_config_t spi_bus_cfg = { 137 | .miso_io_num=miso, 138 | .mosi_io_num=mosi, 139 | .sclk_io_num=sclk, 140 | .quadwp_io_num=-1, 141 | .quadhd_io_num=-1 142 | }; 143 | return (spi_bus_initialize(host, &spi_bus_cfg, 1) == ESP_OK); 144 | } 145 | 146 | bool spi_device_init (uint8_t bus, uint8_t cs) 147 | { 148 | if (bus >= SPI_MAX_BUS || cs >= SPI_MAX_CS) 149 | return false; 150 | 151 | if ((spi_handles[cs] = malloc (sizeof(spi_device_handle_t))) == 0) 152 | return false; 153 | 154 | spi_device_interface_config_t dev_cfg = { 155 | .clock_speed_hz = 1e6, // 1 MHz clock 156 | .mode = 0, // SPI mode 0 157 | .spics_io_num = cs, // CS GPIO 158 | .queue_size = 1, 159 | .flags = 0, // no flags set 160 | .command_bits = 0, // no command bits used 161 | .address_bits = 0, // register address is first byte in MOSI 162 | .dummy_bits = 0 // no dummy bits used 163 | }; 164 | 165 | if (spi_bus_add_device(bus, &dev_cfg, &(spi_handles[cs])) != ESP_OK) 166 | { 167 | free (spi_handles[cs]); 168 | return false; 169 | } 170 | 171 | return true; 172 | } 173 | 174 | size_t spi_transfer_pf (uint8_t bus, uint8_t cs, const uint8_t *mosi, uint8_t *miso, uint16_t len) 175 | { 176 | spi_transaction_t spi_trans; 177 | 178 | if (cs >= SPI_MAX_CS) 179 | return 0; 180 | 181 | memset(&spi_trans, 0, sizeof(spi_trans)); // zero out spi_trans; 182 | spi_trans.tx_buffer = mosi; 183 | spi_trans.rx_buffer = miso; 184 | spi_trans.length=len*8; 185 | 186 | if (spi_device_transmit(spi_handles[cs], &spi_trans) != ESP_OK) 187 | return 0; 188 | 189 | return len; 190 | } 191 | 192 | #endif // ESP32 (ESP-IDF) 193 | 194 | -------------------------------------------------------------------------------- /components/bme680/bme680_types.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure 3 | * and gas sensor connected to I2C or SPI 4 | * 5 | * This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos) 6 | * [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32 7 | * and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux 8 | * based systems using a wrapper library for ESP8266 functions. 9 | * 10 | * --------------------------------------------------------------------------- 11 | * 12 | * The BSD License (3-clause license) 13 | * 14 | * Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht) 15 | * All rights reserved. 16 | * 17 | * Redistribution and use in source and binary forms, with or without 18 | * modification, are permitted provided that the following conditions are met: 19 | * 20 | * 1. Redistributions of source code must retain the above copyright notice, 21 | * this list of conditions and the following disclaimer. 22 | * 23 | * 2. Redistributions in binary form must reproduce the above copyright 24 | * notice, this list of conditions and the following disclaimer in the 25 | * documentation and/or other materials provided with the distribution. 26 | * 27 | * 3. Neither the name of the copyright holder nor the names of its 28 | * contributors may be used to endorse or promote products derived from this 29 | * software without specific prior written permission. 30 | * 31 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 32 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 33 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 34 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 35 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 36 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 37 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 38 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 39 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 40 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 41 | * POSSIBILITY OF SUCH DAMAGE. 42 | */ 43 | 44 | #ifndef __BME680_TYPES_H__ 45 | #define __BME680_TYPES_H__ 46 | 47 | #include "stdint.h" 48 | #include "stdbool.h" 49 | 50 | #ifdef __cplusplus 51 | extern "C" 52 | { 53 | #endif 54 | 55 | /** 56 | * @brief Fixed point sensor values (fixed THPG values) 57 | */ 58 | typedef struct { // invalid value 59 | int16_t temperature; // temperature in degree C * 100 (INT16_MIN) 60 | uint32_t pressure; // barometric pressure in Pascal (0) 61 | uint32_t humidity; // relative humidity in % * 1000 (0) 62 | uint32_t gas_resistance; // gas resistance in Ohm (0) 63 | } bme680_values_fixed_t; 64 | 65 | /** 66 | * @brief Floating point sensor values (real THPG values) 67 | */ 68 | typedef struct { // invalid value 69 | float temperature; // temperature in degree C (-327.68) 70 | float pressure; // barometric pressure in hPascal (0.0) 71 | float humidity; // relative humidity in % (0.0) 72 | float gas_resistance; // gas resistance in Ohm (0.0) 73 | } bme680_values_float_t; 74 | 75 | 76 | /** 77 | * @brief Oversampling rates 78 | */ 79 | typedef enum { 80 | osr_none = 0, // measurement is skipped, output values are invalid 81 | osr_1x = 1, // default oversampling rates 82 | osr_2x = 2, 83 | osr_4x = 3, 84 | osr_8x = 4, 85 | osr_16x = 5 86 | } bme680_oversampling_rate_t; 87 | 88 | 89 | /** 90 | * @brief Filter sizes 91 | */ 92 | typedef enum { 93 | iir_size_0 = 0, // filter is not used 94 | iir_size_1 = 1, 95 | iir_size_3 = 2, 96 | iir_size_7 = 3, 97 | iir_size_15 = 4, 98 | iir_size_31 = 5, 99 | iir_size_63 = 6, 100 | iir_size_127 = 7 101 | } bme680_filter_size_t; 102 | 103 | 104 | /** 105 | * @brief Sensor parameters that configure the TPHG measurement cycle 106 | * 107 | * T - temperature measurement 108 | * P - pressure measurement 109 | * H - humidity measurement 110 | * G - gas measurement 111 | */ 112 | typedef struct { 113 | 114 | uint8_t osr_temperature; // T oversampling rate (default osr_1x) 115 | uint8_t osr_pressure; // P oversampling rate (default osr_1x) 116 | uint8_t osr_humidity; // H oversampling rate (default osr_1x) 117 | uint8_t filter_size; // IIR filter size (default iir_size_3) 118 | 119 | int8_t heater_profile; // Heater profile used (default 0) 120 | uint16_t heater_temperature[10]; // Heater temperature for G (default 320) 121 | uint16_t heater_duration[10]; // Heater duration for G (default 150) 122 | 123 | int8_t ambient_temperature; // Ambient temperature for G (default 25) 124 | 125 | } bme680_settings_t; 126 | 127 | /** 128 | * @brief Data structure for calibration parameters 129 | * 130 | * These calibration parameters are used in compensation algorithms to convert 131 | * raw sensor data to measurement results. 132 | */ 133 | typedef struct { 134 | 135 | uint16_t par_t1; // calibration data for temperature compensation 136 | int16_t par_t2; 137 | int8_t par_t3; 138 | 139 | uint16_t par_p1; // calibration data for pressure compensation 140 | int16_t par_p2; 141 | int8_t par_p3; 142 | int16_t par_p4; 143 | int16_t par_p5; 144 | int8_t par_p7; 145 | int8_t par_p6; 146 | int16_t par_p8; 147 | int16_t par_p9; 148 | uint8_t par_p10; 149 | 150 | uint16_t par_h1; // calibration data for humidity compensation 151 | uint16_t par_h2; 152 | int8_t par_h3; 153 | int8_t par_h4; 154 | int8_t par_h5; 155 | uint8_t par_h6; 156 | int8_t par_h7; 157 | 158 | int8_t par_gh1; // calibration data for gas compensation 159 | int16_t par_gh2; 160 | int8_t par_gh3; 161 | 162 | int32_t t_fine; // temperatur correction factor for P and G 163 | uint8_t res_heat_range; 164 | int8_t res_heat_val; 165 | int8_t range_sw_err; 166 | 167 | } bme680_calib_data_t; 168 | 169 | 170 | /** 171 | * @brief BME680 sensor device data structure type 172 | */ 173 | typedef struct { 174 | 175 | int error_code; // contains the error code of last operation 176 | 177 | uint8_t bus; // I2C = x, SPI = 1 178 | uint8_t addr; // I2C = slave address, SPI = 0 179 | uint8_t cs; // ESP8266, ESP32: GPIO used as SPI CS 180 | // __linux__: device index 181 | 182 | bool meas_started; // indicates whether measurement started 183 | uint8_t meas_status; // last sensor status (for internal use only) 184 | 185 | bme680_settings_t settings; // sensor settings 186 | bme680_calib_data_t calib_data; // calibration data of the sensor 187 | 188 | } bme680_sensor_t; 189 | 190 | 191 | #ifdef __cplusplus 192 | } 193 | #endif /* End of CPP guard */ 194 | 195 | #endif /* __BME680_TYPES_H__ */ 196 | -------------------------------------------------------------------------------- /components/bme680/bme680.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure 3 | * and gas sensor connected to I2C or SPI 4 | * 5 | * This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos) 6 | * [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32 7 | * and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux 8 | * based systems using a wrapper library for ESP8266 functions. 9 | * 10 | * --------------------------------------------------------------------------- 11 | * 12 | * The BSD License (3-clause license) 13 | * 14 | * Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht) 15 | * All rights reserved. 16 | * 17 | * Redistribution and use in source and binary forms, with or without 18 | * modification, are permitted provided that the following conditions are met: 19 | * 20 | * 1. Redistributions of source code must retain the above copyright notice, 21 | * this list of conditions and the following disclaimer. 22 | * 23 | * 2. Redistributions in binary form must reproduce the above copyright 24 | * notice, this list of conditions and the following disclaimer in the 25 | * documentation and/or other materials provided with the distribution. 26 | * 27 | * 3. Neither the name of the copyright holder nor the names of its 28 | * contributors may be used to endorse or promote products derived from this 29 | * software without specific prior written permission. 30 | * 31 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 32 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 33 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 34 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 35 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 36 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 37 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 38 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 39 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 40 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 41 | * POSSIBILITY OF SUCH DAMAGE. 42 | */ 43 | 44 | #ifndef __BME680_H__ 45 | #define __BME680_H__ 46 | 47 | // Uncomment one of the following defines to enable debug output 48 | // #define BME680_DEBUG_LEVEL_1 // only error messages 49 | // #define BME680_DEBUG_LEVEL_2 // debug and error messages 50 | 51 | #include "bme680_types.h" 52 | #include "bme680_platform.h" 53 | 54 | // BME680 addresses 55 | #define BME680_I2C_ADDRESS_1 0x76 // SDO pin is low 56 | #define BME680_I2C_ADDRESS_2 0x77 // SDO pin is high 57 | 58 | // BME680 chip id 59 | #define BME680_CHIP_ID 0x61 // BME680_REG_ID<7:0> 60 | 61 | // Definition of error codes 62 | #define BME680_OK 0 63 | #define BME680_NOK -1 64 | 65 | #define BME680_INT_ERROR_MASK 0x000f 66 | #define BME680_DRV_ERROR_MASK 0xfff0 67 | 68 | // Error codes for I2C and SPI interfaces ORed with BME680 driver error codes 69 | #define BME680_I2C_READ_FAILED 1 70 | #define BME680_I2C_WRITE_FAILED 2 71 | #define BME680_I2C_BUSY 3 72 | #define BME680_SPI_WRITE_FAILED 4 73 | #define BME680_SPI_READ_FAILED 5 74 | #define BME680_SPI_BUFFER_OVERFLOW 6 75 | #define BME680_SPI_SET_PAGE_FAILED 7 76 | 77 | // BME680 driver error codes ORed with error codes for I2C and SPI interfaces 78 | #define BME680_RESET_CMD_FAILED ( 1 << 8) 79 | #define BME680_WRONG_CHIP_ID ( 2 << 8) 80 | #define BME680_READ_CALIB_DATA_FAILED ( 3 << 8) 81 | #define BME680_MEAS_ALREADY_RUNNING ( 4 << 8) 82 | #define BME680_MEAS_NOT_RUNNING ( 5 << 8) 83 | #define BME680_MEAS_STILL_RUNNING ( 6 << 8) 84 | #define BME680_FORCE_MODE_FAILED ( 7 << 8) 85 | #define BME680_NO_NEW_DATA ( 8 << 8) 86 | #define BME680_WRONG_HEAT_PROFILE ( 9 << 8) 87 | #define BME680_MEAS_GAS_NOT_VALID (10 << 8) 88 | #define BME680_HEATER_NOT_STABLE (11 << 8) 89 | 90 | // Driver range definitions 91 | #define BME680_HEATER_TEMP_MIN 200 // min. 200 degree Celsius 92 | #define BME680_HEATER_TEMP_MAX 400 // max. 200 degree Celsius 93 | #define BME680_HEATER_PROFILES 10 // max. 10 heater profiles 0 ... 9 94 | #define BME680_HEATER_NOT_USED -1 // heater not used profile 95 | 96 | #ifdef __cplusplus 97 | extern "C" 98 | { 99 | #endif 100 | 101 | /** -------------------------------------------------------------------------- 102 | * 103 | * Functional Description of the BME680 sensor 104 | * 105 | * The BME680 sensor only support two modes, the sleep mode and the forced 106 | * mode in which measurements are done. After power-up sequence, the sensor 107 | * automatically starts in sleep mode. To start a measurement, the sensor has 108 | * to switch in the forced mode. In this mode it performs exactly one 109 | * measurement of temperature, pressure, humidity, and gas in that order, 110 | * the so-called TPHG measurement cycle. After the execution of this TPHG 111 | * measurement cycle, raw sensor data are available and the sensor returns 112 | * automatically back to sleep mode. 113 | * 114 | * Using the BME680 consists of the following steps 115 | * 116 | * 1. Trigger the sensor to switch into forced mode to perform one THPG cycle 117 | * 2. Wait until the THPG cycle has been finished (measurement duration) 118 | * 3. Fetch raw sensor data, compensate and convert them to sensor values 119 | * 120 | * --------------------------------------------------------------------------- 121 | */ 122 | 123 | /** 124 | * @brief Initialize a BME680 sensor 125 | * 126 | * The function initializes the sensor device data structure, probes the 127 | * sensor, soft resets the sensor, and configures the sensor with the 128 | * the following default settings: 129 | * 130 | * - Oversampling rate for temperature, pressure, humidity is osr_1x 131 | * - Filter size for pressure and temperature is iir_size 3 132 | * - Heater profile 0 with 320 degree C and 150 ms duration 133 | * 134 | * The sensor can be connected either to an I2C or a SPI bus. In both cases, 135 | * the parameter *bus* specifies the ID of the corresponding bus. Please note 136 | * that in case of SPI, bus 1 has to be used since bus 0 is used for system 137 | * flash memory. 138 | * 139 | * If parameter *addr* is greater than 0, it defines a valid I2C slave address 140 | * and the sensor is connected to an I2C bus. In that case parameter *cs* is 141 | * ignored. 142 | * 143 | * If parameter *addr* is 0, the sensor is connected to a SPI bus. In that 144 | * case, parameter *cs* defines the GPIO used as CS signal 145 | * 146 | * @param bus I2C or SPI bus at which BME680 sensor is connected 147 | * @param addr I2C addr of the BME680 sensor, 0 for SPI 148 | * @param cs SPI CS GPIO, ignored for I2C 149 | * @return pointer to sensor data structure, or NULL on error 150 | */ 151 | bme680_sensor_t* bme680_init_sensor (uint8_t bus, uint8_t addr, uint8_t cs); 152 | 153 | /** 154 | * @brief Force one single TPHG measurement 155 | * 156 | * The function triggers the sensor to start one THPG measurement cycle. 157 | * Parameters for the measurement like oversampling rates, IIR filter sizes 158 | * and heater profile can be configured before. 159 | * 160 | * Once the TPHG measurement is started, the user task has to wait for the 161 | * results. The duration of the TPHG measurement can be determined with 162 | * function *bme680_get_measurement_duration*. 163 | * 164 | * @param dev pointer to the sensor device data structure 165 | * @return true on success, false on error 166 | */ 167 | bool bme680_force_measurement (bme680_sensor_t* dev); 168 | 169 | 170 | /** 171 | * @brief Get estimated duration of a TPHG measurement 172 | * 173 | * The function returns an estimated duration of the TPHG measurement cycle 174 | * in RTOS ticks for the current configuration of the sensor. 175 | * 176 | * This duration is the time required by the sensor for one TPHG measurement 177 | * until the results are available. It strongly depends on which measurements 178 | * are performed in the THPG measurement cycle and what configuration 179 | * parameters were set. It can vary from 1 RTOS (10 ms) tick up to 4500 RTOS 180 | * ticks (4.5 seconds). 181 | * 182 | * If the measurement configuration is not changed, the duration can be 183 | * considered as constant. 184 | * 185 | * @param dev pointer to the sensor device data structure 186 | * @return duration of TPHG measurement cycle in ticks or 0 on error 187 | */ 188 | uint32_t bme680_get_measurement_duration (const bme680_sensor_t *dev); 189 | 190 | /** 191 | * @brief Get the measurement status 192 | * 193 | * The function can be used to test whether a measurement that was started 194 | * before is still running. 195 | * 196 | * @param dev pointer to the sensor device data structure 197 | * @return true if measurement is still running or false otherwise 198 | */ 199 | bool bme680_is_measuring (bme680_sensor_t* dev); 200 | 201 | 202 | /** 203 | * @brief Get results of a measurement in fixed point representation 204 | * 205 | * The function returns the results of a TPHG measurement that has been 206 | * started before. If the measurement is still running, the function fails 207 | * and returns invalid values (see type declaration). 208 | * 209 | * @param dev pointer to the sensor device data structure 210 | * @param results pointer to a data structure that is filled with results 211 | * @return true on success, false on error 212 | */ 213 | bool bme680_get_results_fixed (bme680_sensor_t* dev, 214 | bme680_values_fixed_t* results); 215 | 216 | /** 217 | * @brief Get results of a measurement in floating point representation 218 | * 219 | * The function returns the results of a TPHG measurement that has been 220 | * started before. If the measurement is still running, the function fails 221 | * and returns invalid values (see type declaration). 222 | * 223 | * @param dev pointer to the sensor device data structure 224 | * @param results pointer to a data structure that is filled with results 225 | * @return true on success, false on error 226 | */ 227 | bool bme680_get_results_float (bme680_sensor_t* dev, 228 | bme680_values_float_t* results); 229 | 230 | /** 231 | * @brief Start a measurement, wait and return the results (fixed point) 232 | * 233 | * This function is a combination of functions above. For convenience it 234 | * starts a TPHG measurement using *bme680_force_measurement*, then it waits 235 | * the measurement duration for the results using *vTaskDelay* and finally it 236 | * returns the results using function *bme680_get_results_fixed*. 237 | * 238 | * Note: Since the calling task is delayed using function *vTaskDelay*, this 239 | * function must not be used when it is called from a software timer callback 240 | * function. 241 | * 242 | * @param dev pointer to the sensor device data structure 243 | * @param results pointer to a data structure that is filled with results 244 | * @return true on success, false on error 245 | */ 246 | bool bme680_measure_fixed (bme680_sensor_t* dev, 247 | bme680_values_fixed_t* results); 248 | 249 | 250 | /** 251 | * @brief Start a measurement, wait and return the results (floating point) 252 | * 253 | * This function is a combination of functions above. For convenience it 254 | * starts a TPHG measurement using *bme680_force_measurement*, then it waits 255 | * the measurement duration for the results using *vTaskDelay* and finally it 256 | * returns the results using function *bme680_get_results_float*. 257 | * 258 | * Note: Since the calling task is delayed using function *vTaskDelay*, this 259 | * function must not be used when it is called from a software timer callback 260 | * function. 261 | * 262 | * @param dev pointer to the sensor device data structure 263 | * @param results pointer to a data structure that is filled with results 264 | * @return true on success, false on error 265 | */ 266 | bool bme680_measure_float (bme680_sensor_t* dev, 267 | bme680_values_float_t* results); 268 | 269 | /** 270 | * @brief Set the oversampling rates for measurements 271 | * 272 | * The BME680 sensor allows to define individual oversampling rates for 273 | * the measurements of temperature, pressure and humidity. Using an 274 | * oversampling rate of *osr*, the resolution of raw sensor data can be 275 | * increased by ld(*osr*) bits. 276 | * 277 | * Possible oversampling rates are 1x (default), 2x, 4x, 8x, 16x, see type 278 | * *bme680_oversampling_rate_t*. The default oversampling rate is 1. 279 | * 280 | * Please note: Use *osr_none* to skip the corresponding measurement. 281 | * 282 | * @param dev pointer to the sensor device data structure 283 | * @param ost oversampling rate for temperature measurements 284 | * @param osp oversampling rate for pressure measurements 285 | * @param osh oversampling rate for humidity measurements 286 | * @return true on success, false on error 287 | */ 288 | bool bme680_set_oversampling_rates (bme680_sensor_t* dev, 289 | bme680_oversampling_rate_t osr_t, 290 | bme680_oversampling_rate_t osr_p, 291 | bme680_oversampling_rate_t osr_h); 292 | 293 | 294 | /** 295 | * @brief Set the size of the IIR filter 296 | * 297 | * The sensor integrates an internal IIR filter (low pass filter) to reduce 298 | * short-term changes in sensor output values caused by external disturbances. 299 | * It effectively reduces the bandwidth of the sensor output values. 300 | * 301 | * The filter can optionally be used for pressure and temperature data that 302 | * are subject to many short-term changes. Using the IIR filter, increases the 303 | * resolution of pressure and temperature data to 20 bit. Humidity and gas 304 | * inside the sensor does not fluctuate rapidly and does not require such a 305 | * low pass filtering. 306 | * 307 | * The default filter size is 3 (*iir_size_3*). 308 | * 309 | * Please note: If the size of the filter is 0, the filter is not used. 310 | * 311 | * @param dev pointer to the sensor device data structure 312 | * @param size IIR filter size 313 | * @return true on success, false on error 314 | */ 315 | bool bme680_set_filter_size(bme680_sensor_t* dev, bme680_filter_size_t size); 316 | 317 | 318 | /** 319 | * @brief Set a heater profile for gas measurements 320 | * 321 | * The sensor integrates a heater for the gas measurement. Parameters for this 322 | * heater are defined by so called heater profiles. The sensor supports up to 323 | * 10 heater profiles, which are numbered from 0 to 9. Each profile consists of 324 | * a temperature set-point (the target temperature) and a heating duration. 325 | * 326 | * This function sets the parameters for one of the heater profiles 0 ... 9. 327 | * To activate the gas measurement with this profile, use function 328 | * *bme680_use_heater_profile*, see below. 329 | * 330 | * Please note: According to the data sheet, a target temperatures of between 331 | * 200 and 400 degrees Celsius are typical and about 20 to 30 ms are necessary 332 | * for the heater to reach the desired target temperature. 333 | * 334 | * @param dev pointer to the sensor device data structure 335 | * @param profile heater profile 0 ... 9 336 | * @param temperature target temperature in degree Celsius 337 | * @param duration heating duration in milliseconds 338 | * @return true on success, false on error 339 | */ 340 | bool bme680_set_heater_profile (bme680_sensor_t* dev, 341 | uint8_t profile, 342 | uint16_t temperature, 343 | uint16_t duration); 344 | 345 | /** 346 | * @brief Activate gas measurement with a given heater profile 347 | * 348 | * The function activates the gas measurement with one of the heater 349 | * profiles 0 ... 9 or deactivates the gas measurement completely when 350 | * -1 or BME680_HEATER_NOT_USED is used as heater profile. 351 | * 352 | * Parameters of the activated heater profile have to be set before with 353 | * function *bme680_set_heater_profile* otherwise the function fails. 354 | * 355 | * If several heater profiles have been defined with function 356 | * *bme680_set_heater_profile*, a sequence of gas measurements with different 357 | * heater parameters can be realized by a sequence of activations of different 358 | * heater profiles for successive TPHG measurements using this function. 359 | * 360 | * @param dev pointer to the sensor device data structure0 * 361 | * @param profile 0 ... 9 to activate or -1 to deactivate gas measure 362 | * @return true on success, false on error 363 | */ 364 | bool bme680_use_heater_profile (bme680_sensor_t* dev, int8_t profile); 365 | 366 | /** 367 | * @brief Set ambient temperature 368 | * 369 | * The heater resistance calculation algorithm takes into account the ambient 370 | * temperature of the sensor. This function can be used to set this ambient 371 | * temperature. Either values determined from the sensor itself or from 372 | * another temperature sensor can be used. The default ambient temperature 373 | * is 25 degree Celsius. 374 | * 375 | * @param dev pointer to the sensor device data structure 376 | * @param temperature ambient temperature in degree Celsius 377 | * @return true on success, false on error 378 | */ 379 | bool bme680_set_ambient_temperature (bme680_sensor_t* dev, 380 | int16_t temperature); 381 | 382 | 383 | #ifdef __cplusplus 384 | } 385 | #endif /* End of CPP guard */ 386 | 387 | #endif /* __BME680_H__ */ 388 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Driver for **BME680** digital **environmental sensor** 2 | 3 | The driver supports multiple BME680 sensors which are either connected to the SPI or to the same or different I2C interfaces with different addresses. 4 | 5 | It is for the usage with the ESP8266 and [esp-open-rtos](https://github.com/SuperHouse/esp-open-rtos). 6 | The driver is also working with ESP32 and [ESP-IDF](https://github.com/espressif/esp-idf.git) using a wrapper component for ESP8266 functions, see folder ```components/esp8266_wrapper```, as well as Linux based systems using a wrapper library. 7 | 8 | ## About the sensor 9 | 10 | BME680 is an ultra-low-power environmental sensor that integrates temperature, pressure, humidity and gas sensors in only one unit. 11 | 12 | ## Communication interfaces 13 | 14 | The BME680 sensor can be connected using I2C or SPI. 15 | 16 | The I2C interface supports data rates up to 3.4 Mbps. It is possible to connect multiple BME680 sensors with different I2C slave addresses to the same I2C bus or to different I2C buses. Possible I2C slave addresses are 0x76 and 0x77. 17 | 18 | The SPI interface allows clock rates up to 10 MHz and the SPI modes '00' (CPOL=CPHA=0) and '11' (CPOL=CPHA=1). 19 | 20 | Interface selection is done automatically by the sensor using the SPI CS signal. As long as the CS signal keeps high after power-on reset, the I2C interface is used. Once the CS signal has been pulled down, SPI interface is used until next power-on reset. 21 | 22 | ## Measurement process 23 | 24 | Once the BME680 has been initialized, it can be used for measurements. The BME680 operates in two different modes, the **sleep mode** and the **forced mode**. 25 | 26 | The sensor starts after power-up automatically in the *sleep mode* where it does not perform any measurement and consumes only 0.15 μA. Measurements are only done in *forced mode*. 27 | 28 | **Please note:** There are two further undocumented modes, the *parallel* and the *sequential* mode. They can't be supported by the driver, since it is not clear what they do and how to use them. 29 | 30 | #### Measurement cylce 31 | 32 | To perform measurements, the BME680 sensor has to be triggered to switch to the **forced mode**. In this mode, it performs exactly one measurement of temperature, pressure, humidity, and gas in that order, the so-called **TPHG measurement cycle**. After the execution of this TPHG measurement cycle, **raw sensor data** become available and the sensor returns automatically back to sleep mode. 33 | 34 | Each of the individual measurements can be configured or skipped separately via the sensor settings, see section **Measurement settings**. Dependent on the configuration, the **duration of a TPHG measurement cycle** can vary from some milliseconds up to about 4.5 seconds, especially if gas measurement is enabled. 35 | 36 | To avoid the blocking of the user task during measurements, the measurement process is therefore separated into the following steps: 37 | 38 | 1. Trigger the sensor with function ```bme680_force_measurement``` to switch to *forced mode* in which it performs exactly one THPG measurement cycle. 39 | 40 | 2. Wait the measurement duration using function ```vTaskDelay``` and the value returned from function ```bme680_get_measurement_duration``` or wait as long as function ```bme680_is_measuring``` returns true. 41 | 42 | 3. Fetch the results as fixed point values with function ```bme680_get_results_fixed``` or as floating point values with function ```bme680_get_results_float```. 43 | 44 | ``` 45 | ... 46 | // as long as sensor configuration isn't changed, the duration can be considered as constant 47 | uint32_t duration = bme680_get_measurement_duration(sensor); 48 | ... 49 | if (bme680_force_measurement (sensor)) // STEP 1 50 | { 51 | // STEP 2: passive waiting until measurement results are available 52 | vTaskDelay (duration); 53 | 54 | // STEP 3: get the results and do something with them 55 | if (bme680_get_results_float (sensor, &values)) 56 | ... 57 | } 58 | ... 59 | ``` 60 | Alternatively, busy waiting can be realized using function ```bme680_is_measuring```. 61 | ``` 62 | ... 63 | if (bme680_force_measurement (sensor)) // STEP 1 64 | { 65 | // STEP 2: busy waiting until measurement results are available 66 | while (bme680_is_measuring (sensor)) ; 67 | 68 | // STEP 3: get the results and do something with them 69 | if (bme680_get_results_float (sensor, &values)) 70 | ... 71 | } 72 | ... 73 | ``` 74 | 75 | For convenience, it is also possible to use the high-level functions ```bme680_measure_float``` or ```bme680_measure_fixed```. These functions combine all 3 steps above within a single function and are therefore very easy to use. **Please note** that these functions must not be used when they are called from a software timer callback function since the calling task is delayed using function *vTaskDelay*. 76 | 77 | ``` 78 | ... 79 | // ONE STEP: measure, wait, get the results and do something with them 80 | if (bme680_measure_float (sensor, &values)) 81 | ... 82 | ... 83 | ``` 84 | 85 | #### Measurement results 86 | 87 | Once the sensor has finished the measurement raw data are available at the sensor. Either function ```bme680_get_results_fixed``` or function ```bme680_get_results_float``` can be used to fetch the results. Both functions read raw data from the sensor and converts them into utilizable fixed point or floating point sensor values. 88 | 89 | **Please note:** Conversion of raw sensor data into the final sensor values is based on very complex calculations that use a large number of calibration parameters. Therefore, the driver does not provide functions that only return the raw sensor data. 90 | 91 | Dependent on sensor value representation, measurement results contain different dimensions: 92 | 93 | | Value | Fixed Point | Floating Point | Conversion 94 | | ----------- | ------------- | -------- |----------- 95 | | temperature | 1/100 °C | °C | float = fixed / 100 96 | | pressure | Pascal | hPascal | float = fixed / 100 97 | | humidity | 1/1000 % | % | float = fixed / 1000 98 | | gas_resistance | Ohm | Ohm | float = fixed 99 | 100 | The gas resistance value in Ohm represents the resistance of sensor's gas sensitive layer. 101 | 102 | If the TPHG measurement cycle or fetching the results fails, invalid sensor values are returned: 103 | 104 | | Invalid Value | Fixed Point | Floating Point | 105 | | ----------- | ------------- | -------- | 106 | | temperature | INT16_MIN | -327.68 | 107 | | pressure | 0 | 0.0 | 108 | | humidity | 0 | 0.0 | 109 | | gas_resistance | 0 | 0.0 | 110 | 111 | 112 | ## Measurement settings 113 | 114 | The sensor allows to change a lot of measurement parameters. 115 | 116 | #### Oversampling rates 117 | 118 | To increase the resolution of raw sensor data, the sensor supports oversampling for temperature, pressure, and humidity measurements. Using function ```bme680_set_oversampling_rates```, individual **oversampling rates** can be defined for these measurements. With an oversampling rate *osr*, the resolution of the according raw sensor data can be increased from 16 bit to 16+ld(*osr*) bit. 119 | 120 | Possible oversampling rates are 1x (default by the driver) 2x, 4x, 8x and 16x. It is also possible to define an oversampling rate of 0. This **deactivates** the corresponding measurement and the output values become invalid. 121 | 122 | ``` 123 | ... 124 | // Changes the oversampling rate for temperature to 4x and for pressure to 2x. Humidity measurement is skipped. 125 | bme680_set_oversampling_rates(sensor, osr_4x, osr_2x, osr_none); 126 | ... 127 | ``` 128 | 129 | #### IIR Filter 130 | 131 | The sensor also integrates an internal IIR filter (low pass filter) to reduce short-term changes in sensor output values caused by external disturbances. It effectively reduces the bandwidth of the sensor output values. 132 | 133 | The filter can optionally be used for pressure and temperature data that are subject to many short-term changes. With the IIR filter the resolution of pressure and temperature data increases to 20 bit. Humidity and gas inside the sensor does not fluctuate rapidly and does not require such a low pass filtering. 134 | 135 | Using function ```bme680_set_filter_size```, the user task can change the **size of the filter**. The default size is 3. If the size of the filter becomes 0, the filter is **not used**. 136 | 137 | ``` 138 | ... 139 | // Change the IIR filter size for temperature and pressure to 7. 140 | bme680_set_filter_size(sensor, iir_size_7); 141 | ... 142 | // Don't use IIR filter 143 | bme680_set_filter_size(sensor, iir_size_0); 144 | ... 145 | ``` 146 | 147 | #### Heater profile 148 | 149 | For the gas measurement, the sensor integrates a heater. Parameters for this heater are defined by **heater profiles**. The sensor supports up to 10 such heater profiles, which are numbered from 0 to 9. Each profile consists of a temperature set-point (the target temperature) and a heating duration. By default, only the heater profile 0 with 320 degree Celsius as target temperature and 150 ms heating duration is defined. 150 | 151 | **Please note:** According to the data sheet, target temperatures between 200 and 400 degrees Celsius are typical and about 20 to 30 ms are necessary for the heater to reach the desired target temperature. 152 | 153 | Function ```bme680_set_heater_profile``` can be used to set the parameters for one of the heater profiles 0 ... 9. Once the parameters of a heater profile are defined, the gas measurement can be activated with that heater profile using function ```bme680_use_heater_profile```. If -1 or ```BME680_HEATER_NOT_USED``` is used as heater profile, gas measurement is deactivated completely. 154 | 155 | ``` 156 | ... 157 | // Change the heater profile 1 to 300 degree Celsius for 100 ms and activate it 158 | bme680_set_heater_profile (sensor, 1, 300, 100); 159 | bme680_use_heater_profile (sensor, 1); 160 | ... 161 | // Deactivate gas measurement completely 162 | bme680_use_heater_profile (sensor, BME680_HEATER_NOT_USED); 163 | ... 164 | 165 | ``` 166 | 167 | If several heater profiles have been defined with function ```bme680_set_heater_profile```, a sequence of gas measurements with different heater parameters can be realized by a sequence of activations of different heater profiles for successive TPHG measurements using function ```bme680_use_heater_profile```. 168 | 169 | For example, if there were 5 heater profiles defined with following code during the setup 170 | ``` 171 | bme680_set_heater_profile (sensor, 0, 200, 100); 172 | bme680_set_heater_profile (sensor, 1, 250, 120); 173 | bme680_set_heater_profile (sensor, 2, 300, 140); 174 | bme680_set_heater_profile (sensor, 3, 350, 160); 175 | bme680_set_heater_profile (sensor, 4, 400, 180); 176 | ``` 177 | 178 | the user task could use them as a sequence like following: 179 | 180 | ``` 181 | ... 182 | while (1) 183 | { 184 | switch (count++ % 5) 185 | { 186 | case 0: bme680_use_heater_profile (sensor, 0); break; 187 | case 1: bme680_use_heater_profile (sensor, 1); break; 188 | case 2: bme680_use_heater_profile (sensor, 2); break; 189 | case 3: bme680_use_heater_profile (sensor, 3); break; 190 | case 4: bme680_use_heater_profile (sensor, 4); break; 191 | } 192 | 193 | // measurement duration changes in each cycle 194 | uint32_t duration = bme680_get_measurement_duration(sensor); 195 | 196 | // trigger the sensor to start one TPHG measurement cycle 197 | if (bme680_force_measurement (sensor)) 198 | { 199 | vTaskDelay (duration); 200 | 201 | // get the results and do something with them 202 | if (bme680_get_results_float (sensor, &values)) 203 | ... 204 | } 205 | ... 206 | } 207 | ... 208 | ``` 209 | 210 | #### Ambient temperature 211 | 212 | The heater resistance calculation algorithm takes into account the ambient temperature of the sensor. Using function ```bme680_set_ambient_temperature```, the ambient temperature either determined from the sensor itself or from another temperature sensor can be set. 213 | 214 | ``` 215 | ... 216 | bme680_set_ambient_temperature (sensor, ambient); 217 | ... 218 | ``` 219 | 220 | ## Error Handling 221 | 222 | Most driver functions return a simple boolean value to indicate whether its execution was successful or an error happened. In the latter case, the member ```error_code``` of the sensor device data structure is set which indicates what error happened. 223 | 224 | There are two different error levels that are ORed into one single *error_code*, errors in the I2C or SPI communication and errors of the BME680 sensor itself. To test for a certain error, first you can AND the *error_code* with one of the error masks, ```BME680_INT_ERROR_MASK``` for I2C or SPI errors and ```BME680_DRV_ERROR_MASK``` for other errors. Then you can test the result for a certain error code. 225 | 226 | For example, error handling for ```bme680_get_results_float``` could look like: 227 | 228 | ``` 229 | if (bme680_get_results_float (sensor, &values)) 230 | { 231 | // no error happened 232 | ... 233 | } 234 | else 235 | { 236 | // error happened 237 | 238 | switch (sensor->error_code & BME680_INT_ERROR_MASK) 239 | { 240 | case BME680_I2C_BUSY: ... 241 | case BME680_I2C_READ_FAILED: ... 242 | ... 243 | } 244 | switch (sensor->error_code & BME680_DRV_ERROR_MASK) 245 | { 246 | case BME680_MEAS_STILL_RUNNING: ... 247 | case BME680_NO_NEW_DATA: ... 248 | ... 249 | } 250 | } 251 | ``` 252 | 253 | ## Usage 254 | 255 | First, the hardware configuration has to be established. This can differ dependent on the communication interface and the number of sensors used. 256 | 257 | ### Hardware configurations 258 | 259 | The driver supports multiple BME680 sensors at the same time that are connected either to I2C or SPI. Following figures show some possible hardware configurations. 260 | 261 | First figure shows the configuration with only one sensor at I2C bus 0. 262 | 263 | ``` 264 | +------------------+ +----------+ 265 | | ESP8266 / ESP32 | | BME680 | 266 | | | | | 267 | | GPIO 14 (SCL) ----> SCL | 268 | | GPIO 13 (SDA) <---> SDA | 269 | +------------------+ +----------+ 270 | ``` 271 | 272 | Next figure shows the configuration with only one sensor at SPI bus. 273 | 274 | ``` 275 | +------------------+ +----------+ +-----------------+ +----------+ 276 | | ESP8266 / ESP32 | | BME680 | | ESP32 | | BME680 | 277 | | | | | | | | | 278 | | GPIO 14 (SCK) ----> SCK | | GPIO 16 (SCK) ----> SCK | 279 | | GPIO 13 (MOSI) ----> SDI | | GPIO 17 (MOSI)----> SDI | 280 | | GPIO 12 (MISO) <---- SDO | | GPIO 18 (MISO)<---- SDO | 281 | | GPIO 2 (CS) ----> CS | | GPIO 19 (CS) ----> CS | 282 | +------------------+ +---------+ +-----------------+ +----------+ 283 | ``` 284 | 285 | **Please note:** 286 | 287 | 1. Since the system flash memory is connected to SPI bus 0, the sensor has to be connected to SPI bus 1. 288 | 289 | 2. GPIO15 which is used as CS signal of SPI bus 1 on ESP8266 does not work correctly together with the BME680. Therefore, the user has to specify another GPIO pin as CS signal, e.g., GPIO2. 290 | Next figure shows a possible configuration with two I2C buses. In that case, the sensors can have same or different I2C slave addresses. 291 | 292 | ``` 293 | +------------------+ +----------+ 294 | | ESP8266 / ESP32 | | BME680_1 | 295 | | | | | 296 | | GPIO 14 (SCL) ----> SCL | 297 | | GPIO 13 (SDA) <---> SDA | 298 | | | +----------+ 299 | | | | BME680_2 | 300 | | | | | 301 | | GPIO 5 (SCL) ----> SCL | 302 | | GPIO 4 (SDA) <---> SDA | 303 | +------------------+ +----------+ 304 | ``` 305 | 306 | Last figure shows a possible configuration using I2C bus 0 and SPI bus 1 at the same time. 307 | ``` 308 | +------------------+ +----------+ +------------------+ +----------+ 309 | | ESP8266 | | BME680_1 | | ESP8266 | | BME680_1 | 310 | | | | | | | | | 311 | | GPIO 5 (SCL) ----> SCL | | GPIO 5 (SCL) ----> SCL | 312 | | GPIO 4 (SDA) <---> SDA | | GPIO 4 (SDA) <---> SDA | 313 | | | +----------+ | | +----------+ 314 | | | | BME680_2 | | | | BME680_2 | 315 | | GPIO 14 (SCK) ----> SCK | | GPIO 16 (SCK) ----> SCK | 316 | | GPIO 13 (MOSI) ----> SDI | | GPIO 17 (MOSI) ----> SDI | 317 | | GPIO 12 (MISO) <---- SDO | | GPIO 18 (MISO) <---- SDO | 318 | | GPIO 2 (CS) ----> CS | | GPIO 19 (CS) ----> CS | 319 | +------------------+ +---------+ +------------------+ +----------+ 320 | ``` 321 | 322 | Further configurations are possible, e.g., two sensors that are connected at the same I2C bus with different slave addresses. 323 | 324 | ### Communication interface settings 325 | 326 | Dependent on the hardware configuration, the communication interface settings have to be defined. 327 | 328 | ``` 329 | // define SPI interface for BME680 sensors 330 | #define SPI_BUS 1 331 | #define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used 332 | #else 333 | 334 | // define I2C interface for BME680 sensors 335 | #define I2C_BUS 0 336 | #define I2C_SCL_PIN 14 337 | #define I2C_SDA_PIN 13 338 | #endif 339 | 340 | ``` 341 | 342 | ### Main programm 343 | 344 | If I2C interfaces are used, they have to be initialized first. 345 | 346 | ``` 347 | i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ_100K)) 348 | ``` 349 | 350 | SPI interface has not to be initialized explicitly. 351 | 352 | Once the I2C interfaces are initialized, function ```bme680_init_sensor``` has to be called for each BME680 sensor in order to initialize the sensor and to check its availability as well as its error state. This function returns a pointer to a sensor device data structure or NULL in case of error. 353 | 354 | The parameter *bus* specifies the ID of the I2C or SPI bus to which the sensor is connected. 355 | 356 | ``` 357 | static bme680_sensor_t* sensor; 358 | ``` 359 | 360 | For sensors connected to an I2C interface, a valid I2C slave address has to be defined as parameter *addr*. In that case parameter *cs* is ignored. 361 | 362 | ``` 363 | sensor = bme680_init_sensor (I2C_BUS, BME680_I2C_ADDRESS_2, 0); 364 | 365 | ``` 366 | 367 | If parameter *addr* is 0, the sensor is connected to a SPI bus. In that case, parameter *cs* defines the GPIO used as CS signal. 368 | 369 | ``` 370 | sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO); 371 | 372 | ``` 373 | 374 | The remaining part of the program is independent on the communication interface. 375 | 376 | Optionally, you could wish to set some measurement parameters. For details see the section **Measurement settings** above, the header file of the driver ```bme680.h```, and of course the data sheet of the sensor. 377 | 378 | ``` 379 | if (sensor) 380 | { 381 | /** -- SENSOR CONFIGURATION PART (optional) --- */ 382 | 383 | // Changes the oversampling rates to 4x oversampling for temperature 384 | // and 2x oversampling for humidity. Pressure measurement is skipped. 385 | bme680_set_oversampling_rates(sensor, osr_4x, osr_none, osr_2x); 386 | 387 | // Change the IIR filter size for temperature and pressure to 7. 388 | bme680_set_filter_size(sensor, iir_size_7); 389 | 390 | // Change the heater profile 0 to 200 degree Celsius for 100 ms. 391 | bme680_set_heater_profile (sensor, 0, 200, 100); 392 | bme680_use_heater_profile (sensor, 0); 393 | 394 | /** -- TASK CREATION PART --- */ 395 | 396 | // must be done last to avoid concurrency situations with the sensor 397 | // configuration part 398 | 399 | // Create a task that uses the sensor 400 | xTaskCreate(user_task, "user_task", TASK_STACK_DEPTH, NULL, 2, NULL); 401 | 402 | ... 403 | } 404 | ``` 405 | 406 | Finally, a user task that uses the sensor has to be created. 407 | 408 | **Please note:** To avoid concurrency situations when driver functions are used to access the sensor, for example to read data, the user task must not be created until the sensor configuration is completed. 409 | 410 | 411 | ### User task 412 | 413 | BME680 supports only the *forced mode* that performs exactly one measurement. Therefore, the measurement has to be triggered in each cycle. The waiting for measurement results is also required in each cycle, before the results can be fetched. 414 | 415 | Thus the user task could look like the following: 416 | 417 | 418 | ``` 419 | void user_task(void *pvParameters) 420 | { 421 | bme680_values_float_t values; 422 | 423 | TickType_t last_wakeup = xTaskGetTickCount(); 424 | 425 | // as long as sensor configuration isn't changed, duration is constant 426 | uint32_t duration = bme680_get_measurement_duration(sensor); 427 | 428 | while (1) 429 | { 430 | // trigger the sensor to start one TPHG measurement cycle 431 | bme680_force_measurement (sensor); 432 | 433 | // passive waiting until measurement results are available 434 | vTaskDelay (duration); 435 | 436 | // alternatively: busy waiting until measurement results are available 437 | // while (bme680_is_measuring (sensor)) ; 438 | 439 | // get the results and do something with them 440 | if (bme680_get_results_float (sensor, &values)) 441 | printf("%.3f BME680 Sensor: %.2f °C, %.2f %%, %.2f hPa, %.2f Ohm\n", 442 | (double)sdk_system_get_time()*1e-3, 443 | values.temperature, values.humidity, 444 | values.pressure, values.gas_resistance); 445 | 446 | // passive waiting until 1 second is over 447 | vTaskDelayUntil(&last_wakeup, 1000 / portTICK_PERIOD_MS); 448 | } 449 | } 450 | ``` 451 | 452 | Function ```bme680_force_measurement``` is called inside the task loop to perform exactly one measurement in each cycle. 453 | 454 | The task is then delayed using function ```vTaskDelay``` and the value returned from function ```bme680_get_measurement_duration``` or as long as function ```bme680_is_measuring``` returns true. 455 | 456 | Since the measurement duration only depends on the current sensor configuration, it changes only when sensor configuration is changed. Therefore, it can be considered as constant as long as the sensor configuration isn't changed and can be determined with function ```bme680_get_measurement_duration``` outside the task loop. If the sensor configuration changes, the function has to be executed again. 457 | 458 | Once the measurement results are available, they can be fetched as fixed point oder floating point sensor values using function ```bme680_get_results_float``` and ```bme680_get_results_fixed```, respectively. 459 | 460 | ## Full Example 461 | 462 | ``` 463 | /* -- use following constants to define the example mode ----------- */ 464 | 465 | // #define SPI_USED 466 | 467 | /* -- includes ----------------------------------------------------- */ 468 | 469 | #include "bme680.h" 470 | 471 | /* -- platform dependent definitions ------------------------------- */ 472 | 473 | #ifdef ESP_PLATFORM // ESP32 (ESP-IDF) 474 | 475 | // user task stack depth for ESP32 476 | #define TASK_STACK_DEPTH 2048 477 | 478 | // SPI interface definitions for ESP32 479 | #define SPI_BUS HSPI_HOST 480 | #define SPI_SCK_GPIO 16 481 | #define SPI_MOSI_GPIO 17 482 | #define SPI_MISO_GPIO 18 483 | #define SPI_CS_GPIO 19 484 | 485 | #else // ESP8266 (esp-open-rtos) 486 | 487 | // user task stack depth for ESP8266 488 | #define TASK_STACK_DEPTH 256 489 | 490 | // SPI interface definitions for ESP8266 491 | #define SPI_BUS 1 492 | #define SPI_SCK_GPIO 14 493 | #define SPI_MOSI_GPIO 13 494 | #define SPI_MISO_GPIO 12 495 | #define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used 496 | 497 | #endif // ESP_PLATFORM 498 | 499 | // I2C interface defintions for ESP32 and ESP8266 500 | #define I2C_BUS 0 501 | #define I2C_SCL_PIN 14 502 | #define I2C_SDA_PIN 13 503 | #define I2C_FREQ I2C_FREQ_100K 504 | 505 | /* -- user tasks --------------------------------------------------- */ 506 | 507 | static bme680_sensor_t* sensor = 0; 508 | 509 | /* 510 | * User task that triggers measurements of sensor every seconds. It uses 511 | * function *vTaskDelay* to wait for measurement results. Busy wating 512 | * alternative is shown in comments 513 | */ 514 | void user_task(void *pvParameters) 515 | { 516 | bme680_values_float_t values; 517 | 518 | TickType_t last_wakeup = xTaskGetTickCount(); 519 | 520 | // as long as sensor configuration isn't changed, duration is constant 521 | uint32_t duration = bme680_get_measurement_duration(sensor); 522 | 523 | while (1) 524 | { 525 | // trigger the sensor to start one TPHG measurement cycle 526 | if (bme680_force_measurement (sensor)) 527 | { 528 | // passive waiting until measurement results are available 529 | vTaskDelay (duration); 530 | 531 | // alternatively: busy waiting until measurement results are available 532 | // while (bme680_is_measuring (sensor)) ; 533 | 534 | // get the results and do something with them 535 | if (bme680_get_results_float (sensor, &values)) 536 | printf("%.3f BME680 Sensor: %.2f °C, %.2f %%, %.2f hPa, %.2f Ohm\n", 537 | (double)sdk_system_get_time()*1e-3, 538 | values.temperature, values.humidity, 539 | values.pressure, values.gas_resistance); 540 | } 541 | // passive waiting until 1 second is over 542 | vTaskDelayUntil(&last_wakeup, 1000 / portTICK_PERIOD_MS); 543 | } 544 | } 545 | 546 | /* -- main program ------------------------------------------------- */ 547 | 548 | void user_init(void) 549 | { 550 | // Set UART Parameter. 551 | uart_set_baud(0, 115200); 552 | // Give the UART some time to settle 553 | vTaskDelay(1); 554 | 555 | /** -- MANDATORY PART -- */ 556 | 557 | #ifdef SPI_USED 558 | 559 | spi_bus_init (SPI_BUS, SPI_SCK_GPIO, SPI_MISO_GPIO, SPI_MOSI_GPIO); 560 | 561 | // init the sensor connected to SPI_BUS with SPI_CS_GPIO as chip select. 562 | sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO); 563 | 564 | #else // I2C 565 | 566 | // Init all I2C bus interfaces at which BME680 sensors are connected 567 | i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ); 568 | 569 | // init the sensor with slave address BME680_I2C_ADDRESS_2 connected to I2C_BUS. 570 | sensor = bme680_init_sensor (I2C_BUS, BME680_I2C_ADDRESS_2, 0); 571 | 572 | #endif // SPI_USED 573 | 574 | if (sensor) 575 | { 576 | /** -- SENSOR CONFIGURATION PART (optional) --- */ 577 | 578 | // Changes the oversampling rates to 4x oversampling for temperature 579 | // and 2x oversampling for humidity. Pressure measurement is skipped. 580 | bme680_set_oversampling_rates(sensor, osr_4x, osr_none, osr_2x); 581 | 582 | // Change the IIR filter size for temperature and pressure to 7. 583 | bme680_set_filter_size(sensor, iir_size_7); 584 | 585 | // Change the heater profile 0 to 200 degree Celcius for 100 ms. 586 | bme680_set_heater_profile (sensor, 0, 200, 100); 587 | bme680_use_heater_profile (sensor, 0); 588 | 589 | // Set ambient temperature to 10 degree Celsius 590 | bme680_set_ambient_temperature (sensor, 10); 591 | 592 | /** -- TASK CREATION PART --- */ 593 | 594 | // must be done last to avoid concurrency situations with the sensor 595 | // configuration part 596 | 597 | // Create a task that uses the sensor 598 | xTaskCreate(user_task, "user_task", TASK_STACK_DEPTH, NULL, 2, NULL); 599 | } 600 | else 601 | printf("Could not initialize BME680 sensor\n"); 602 | } 603 | ``` 604 | 605 | -------------------------------------------------------------------------------- /components/bme680/bme680.c: -------------------------------------------------------------------------------- 1 | /* 2 | * Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure 3 | * and gas sensor connected to I2C or SPI 4 | * 5 | * This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos) 6 | * [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32 7 | * and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux 8 | * based systems using a wrapper library for ESP8266 functions. 9 | * 10 | * --------------------------------------------------------------------------- 11 | * 12 | * The BSD License (3-clause license) 13 | * 14 | * Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht) 15 | * All rights reserved. 16 | * 17 | * Redistribution and use in source and binary forms, with or without 18 | * modification, are permitted provided that the following conditions are met: 19 | * 20 | * 1. Redistributions of source code must retain the above copyright notice, 21 | * this list of conditions and the following disclaimer. 22 | * 23 | * 2. Redistributions in binary form must reproduce the above copyright 24 | * notice, this list of conditions and the following disclaimer in the 25 | * documentation and/or other materials provided with the distribution. 26 | * 27 | * 3. Neither the name of the copyright holder nor the names of its 28 | * contributors may be used to endorse or promote products derived from this 29 | * software without specific prior written permission. 30 | * 31 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 32 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 33 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 34 | * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 35 | * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 36 | * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 37 | * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 38 | * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 39 | * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 40 | * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 41 | * POSSIBILITY OF SUCH DAMAGE. 42 | * 43 | * The information provided is believed to be accurate and reliable. The 44 | * copyright holder assumes no responsibility for the consequences of use 45 | * of such information nor for any infringement of patents or other rights 46 | * of third parties which may result from its use. No license is granted by 47 | * implication or otherwise under any patent or patent rights of the copyright 48 | * holder. 49 | */ 50 | 51 | #include 52 | #include 53 | 54 | #include "bme680_platform.h" 55 | #include "bme680.h" 56 | 57 | #if defined(BME680_DEBUG_LEVEL_2) 58 | #define debug(s, f, ...) printf("%s %s: " s "\n", "BME680", f, ## __VA_ARGS__) 59 | #define debug_dev(s, f, d, ...) printf("%s %s: bus %d, addr %02x - " s "\n", "BME680", f, d->bus, d->addr, ## __VA_ARGS__) 60 | #else 61 | #define debug(s, f, ...) 62 | #define debug_dev(s, f, d, ...) 63 | #endif 64 | 65 | #if defined(BME680_DEBUG_LEVEL_1) || defined(BME680_DEBUG_LEVEL_2) 66 | #define error(s, f, ...) printf("%s %s: " s "\n", "BME680", f, ## __VA_ARGS__) 67 | #define error_dev(s, f, d, ...) printf("%s %s: bus %d, addr %02x - " s "\n", "BME680", f, d->bus, d->addr, ## __VA_ARGS__) 68 | #else 69 | #define error(s, f, ...) 70 | #define error_dev(s, f, d, ...) 71 | #endif 72 | 73 | // modes: unfortunatly, only SLEEP_MODE and FORCED_MODE are documented 74 | #define BME680_SLEEP_MODE 0x00 // low power sleeping 75 | #define BME680_FORCED_MODE 0x01 // perform one TPHG cycle (field data 0 filled) 76 | #define BME680_PARALLEL_MODE 0x02 // no information what it does :-( 77 | #define BME680_SQUENTUAL_MODE 0x02 // no information what it does (field data 0+1+2 filled) 78 | 79 | // register addresses 80 | #define BME680_REG_RES_HEAT_VAL 0x00 81 | #define BME680_REG_RES_HEAT_RANGE 0x02 82 | #define BME680_REG_RANGE_SW_ERROR 0x06 83 | 84 | #define BME680_REG_IDAC_HEAT_BASE 0x50 // 10 regsrs idac_heat_0 ... idac_heat_9 85 | #define BME680_REG_RES_HEAT_BASE 0x5a // 10 registers res_heat_0 ... res_heat_9 86 | #define BME680_REG_GAS_WAIT_BASE 0x64 // 10 registers gas_wait_0 ... gas_wait_9 87 | #define BME680_REG_CTRL_GAS_0 0x70 88 | #define BME680_REG_CTRL_GAS_1 0x71 89 | #define BME680_REG_CTRL_HUM 0x72 90 | #define BME680_REG_STATUS 0x73 91 | #define BME680_REG_CTRL_MEAS 0x74 92 | #define BME680_REG_CONFIG 0x75 93 | #define BME680_REG_ID 0xd0 94 | #define BME680_REG_RESET 0xe0 95 | 96 | // field data 0 registers 97 | #define BME680_REG_MEAS_STATUS_0 0x1d 98 | #define BME680_REG_MEAS_INDEX_0 0x1e 99 | #define BME680_REG_PRESS_MSB_0 0x1f 100 | #define BME680_REG_PRESS_LSB_0 0x20 101 | #define BME680_REG_PRESS_XLSB_0 0x21 102 | #define BME680_REG_TEMP_MSB_0 0x22 103 | #define BME680_REG_TEMP_LSB_0 0x23 104 | #define BME680_REG_TEMP_XLSB_0 0x24 105 | #define BME680_REG_HUM_MSB_0 0x25 106 | #define BME680_REG_HUM_LSB_0 0x26 107 | #define BME680_REG_GAS_R_MSB_0 0x2a 108 | #define BME680_REG_GAS_R_LSB_0 0x2b 109 | 110 | // field data 1 registers (not documented, used in SEQUENTIAL_MODE) 111 | #define BME680_REG_MEAS_STATUS_1 0x2e 112 | #define BME680_REG_MEAS_INDEX_1 0x2f 113 | 114 | // field data 2 registers (not documented, used in SEQUENTIAL_MODE) 115 | #define BME680_REG_MEAS_STATUS_2 0x3f 116 | #define BME680_REG_MEAS_INDEX_2 0x40 117 | 118 | // field data addresses 119 | #define BME680_REG_RAW_DATA_0 BME680_REG_MEAS_STATUS_0 // 0x1d ... 0x2b 120 | #define BME680_REG_RAW_DATA_1 BME680_REG_MEAS_STATUS_1 // 0x2e ... 0x3c 121 | #define BME680_REG_RAW_DATA_2 BME680_REG_MEAS_STATUS_2 // 0x40 ... 0x4d 122 | #define BME680_REG_RAW_DATA_LEN (BME680_REG_GAS_R_LSB_0 - BME680_REG_MEAS_STATUS_0 + 1) 123 | 124 | // calibration data registers 125 | #define BME680_REG_CD1_ADDR 0x89 // 25 byte calibration data 126 | #define BME680_REG_CD1_LEN 25 127 | #define BME680_REG_CD2_ADDR 0xe1 // 16 byte calibration data 128 | #define BME680_REG_CD2_LEN 16 129 | #define BME680_REG_CD3_ADDR 0x00 // 8 byte device specific calibration data 130 | #define BME680_REG_CD3_LEN 8 131 | 132 | // register structure definitions 133 | #define BME680_NEW_DATA_BITS 0x80 // BME680_REG_MEAS_STATUS<7> 134 | #define BME680_NEW_DATA_SHIFT 7 // BME680_REG_MEAS_STATUS<7> 135 | #define BME680_GAS_MEASURING_BITS 0x40 // BME680_REG_MEAS_STATUS<6> 136 | #define BME680_GAS_MEASURING_SHIFT 6 // BME680_REG_MEAS_STATUS<6> 137 | #define BME680_MEASURING_BITS 0x20 // BME680_REG_MEAS_STATUS<5> 138 | #define BME680_MEASURING_SHIFT 5 // BME680_REG_MEAS_STATUS<5> 139 | #define BME680_GAS_MEAS_INDEX_BITS 0x0f // BME680_REG_MEAS_STATUS<3:0> 140 | #define BME680_GAS_MEAS_INDEX_SHIFT 0 // BME680_REG_MEAS_STATUS<3:0> 141 | 142 | #define BME680_GAS_R_LSB_BITS 0xc0 // BME680_REG_GAS_R_LSB<7:6> 143 | #define BME680_GAS_R_LSB_SHIFT 6 // BME680_REG_GAS_R_LSB<7:6> 144 | #define BME680_GAS_VALID_BITS 0x20 // BME680_REG_GAS_R_LSB<5> 145 | #define BME680_GAS_VALID_SHIFT 5 // BME680_REG_GAS_R_LSB<5> 146 | #define BME680_HEAT_STAB_R_BITS 0x10 // BME680_REG_GAS_R_LSB<4> 147 | #define BME680_HEAT_STAB_R_SHIFT 4 // BME680_REG_GAS_R_LSB<4> 148 | #define BME680_GAS_RANGE_R_BITS 0x0f // BME680_REG_GAS_R_LSB<3:0> 149 | #define BME680_GAS_RANGE_R_SHIFT 0 // BME680_REG_GAS_R_LSB<3:0> 150 | 151 | #define BME680_HEAT_OFF_BITS 0x04 // BME680_REG_CTRL_GAS_0<3> 152 | #define BME680_HEAT_OFF_SHIFT 3 // BME680_REG_CTRL_GAS_0<3> 153 | 154 | #define BME680_RUN_GAS_BITS 0x10 // BME680_REG_CTRL_GAS_1<4> 155 | #define BME680_RUN_GAS_SHIFT 4 // BME680_REG_CTRL_GAS_1<4> 156 | #define BME680_NB_CONV_BITS 0x0f // BME680_REG_CTRL_GAS_1<3:0> 157 | #define BME680_NB_CONV_SHIFT 0 // BME680_REG_CTRL_GAS_1<3:0> 158 | 159 | #define BME680_SPI_3W_INT_EN_BITS 0x40 // BME680_REG_CTRL_HUM<6> 160 | #define BME680_SPI_3W_INT_EN_SHIFT 6 // BME680_REG_CTRL_HUM<6> 161 | #define BME680_OSR_H_BITS 0x07 // BME680_REG_CTRL_HUM<2:0> 162 | #define BME680_OSR_H_SHIFT 0 // BME680_REG_CTRL_HUM<2:0> 163 | 164 | #define BME680_OSR_T_BITS 0xe0 // BME680_REG_CTRL_MEAS<7:5> 165 | #define BME680_OSR_T_SHIFT 5 // BME680_REG_CTRL_MEAS<7:5> 166 | #define BME680_OSR_P_BITS 0x1c // BME680_REG_CTRL_MEAS<4:2> 167 | #define BME680_OSR_P_SHIFT 2 // BME680_REG_CTRL_MEAS<4:2> 168 | #define BME680_MODE_BITS 0x03 // BME680_REG_CTRL_MEAS<1:0> 169 | #define BME680_MODE_SHIFT 0 // BME680_REG_CTRL_MEAS<1:0> 170 | 171 | #define BME680_FILTER_BITS 0x1c // BME680_REG_CONFIG<4:2> 172 | #define BME680_FILTER_SHIFT 2 // BME680_REG_CONFIG<4:2> 173 | #define BME680_SPI_3W_EN_BITS 0x01 // BME680_REG_CONFIG<0> 174 | #define BME680_SPI_3W_EN_SHIFT 0 // BME680_REG_CONFIG<0> 175 | 176 | #define BME680_SPI_MEM_PAGE_BITS 0x10 // BME680_REG_STATUS<4> 177 | #define BME680_SPI_MEM_PAGE_SHIFT 4 // BME680_REG_STATUS<4> 178 | 179 | #define BME680_GAS_WAIT_BITS 0x3f // BME680_REG_GAS_WAIT+x<5:0> 180 | #define BME680_GAS_WAIT_SHIFT 0 // BME680_REG_GAS_WAIT+x<5:0> 181 | #define BME680_GAS_WAIT_MULT_BITS 0xc0 // BME680_REG_GAS_WAIT+x<7:6> 182 | #define BME680_GAS_WAIT_MULT_SHIFT 6 // BME680_REG_GAS_WAIT+x<7:6> 183 | 184 | // commands 185 | #define BME680_RESET_CMD 0xb6 // BME680_REG_RESET<7:0> 186 | #define BME680_RESET_PERIOD 5 // reset time in ms 187 | 188 | #define BME680_RHR_BITS 0x30 // BME680_REG_RES_HEAT_RANGE<5:4> 189 | #define BME680_RHR_SHIFT 4 // BME680_REG_RES_HEAT_RANGE<5:4> 190 | #define BME680_RSWE_BITS 0xf0 // BME680_REG_RANGE_SW_ERROR<7:4> 191 | #define BME680_RSWE_SHIFT 4 // BME680_REG_RANGE_SW_ERROR<7:4> 192 | 193 | // calibration data are stored in a calibration data map 194 | #define BME680_CDM_SIZE (BME680_REG_CD1_LEN + BME680_REG_CD2_LEN + BME680_REG_CD3_LEN) 195 | #define BME680_CDM_OFF1 0 196 | #define BME680_CDM_OFF2 BME680_REG_CD1_LEN 197 | #define BME680_CDM_OFF3 BME680_CDM_OFF2 + BME680_REG_CD2_LEN 198 | 199 | // calibration parameter offsets in calibration data map 200 | // calibration data from 0x89 201 | #define BME680_CDM_T2 1 202 | #define BME680_CDM_T3 3 203 | #define BME680_CDM_P1 5 204 | #define BME680_CDM_P2 7 205 | #define BME680_CDM_P3 9 206 | #define BME680_CDM_P4 11 207 | #define BME680_CDM_P5 13 208 | #define BME680_CDM_P7 15 209 | #define BME680_CDM_P6 16 210 | #define BME680_CDM_P8 19 211 | #define BME680_CDM_P9 21 212 | #define BME680_CDM_P10 23 213 | // calibration data from 0e1 214 | #define BME680_CDM_H2 25 215 | #define BME680_CDM_H1 26 216 | #define BME680_CDM_H3 28 217 | #define BME680_CDM_H4 29 218 | #define BME680_CDM_H5 30 219 | #define BME680_CDM_H6 31 220 | #define BME680_CDM_H7 32 221 | #define BME680_CDM_T1 33 222 | #define BME680_CDM_GH2 35 223 | #define BME680_CDM_GH1 37 224 | #define BME680_CDM_GH3 38 225 | // device specific calibration data from 0x00 226 | #define BME680_CDM_RHV 41 // 0x00 - res_heat_val 227 | #define BME680_CDM_RHR 43 // 0x02 - res_heat_range 228 | #define BME680_CDM_RSWE 45 // 0x04 - range_sw_error 229 | 230 | 231 | /** 232 | * @brief Raw data (integer values) read from sensor 233 | */ 234 | typedef struct { 235 | 236 | bool gas_valid; // indicate that gas measurement results are valid 237 | bool heater_stable; // indicate that heater temperature was stable 238 | 239 | uint32_t temperature; // degree celsius x100 240 | uint32_t pressure; // pressure in Pascal 241 | uint16_t humidity; // relative humidity x1000 in % 242 | uint16_t gas_resistance; // gas resistance data 243 | uint8_t gas_range; // gas resistance range 244 | 245 | uint8_t gas_index; // heater profile used (0 ... 9) 246 | uint8_t meas_index; 247 | 248 | 249 | } bme680_raw_data_t; 250 | 251 | 252 | /** Forward declaration of functions for internal use */ 253 | 254 | static bool bme680_set_mode (bme680_sensor_t* dev, uint8_t mode); 255 | static bool bme680_get_raw_data (bme680_sensor_t* dev, bme680_raw_data_t* raw); 256 | static int16_t bme680_convert_temperature (bme680_sensor_t *dev, uint32_t raw_temperature); 257 | static uint32_t bme680_convert_pressure (bme680_sensor_t *dev, uint32_t raw_pressure); 258 | static uint32_t bme680_convert_humidity (bme680_sensor_t *dev, uint16_t raw_humidity); 259 | static uint32_t bme680_convert_gas (bme680_sensor_t *dev, uint16_t raw_gas, uint8_t gas_range); 260 | 261 | static uint8_t bme680_heater_resistance (const bme680_sensor_t* dev, uint16_t temperature); 262 | static uint8_t bme680_heater_duration (uint16_t duration); 263 | 264 | static bool bme680_reset (bme680_sensor_t* dev); 265 | static bool bme680_is_available (bme680_sensor_t* dev); 266 | static void bme680_delay_ms(uint32_t delay); 267 | 268 | static bool bme680_read_reg (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len); 269 | static bool bme680_write_reg (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len); 270 | static bool bme680_i2c_read (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len); 271 | static bool bme680_i2c_write (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len); 272 | static bool bme680_spi_read (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len); 273 | static bool bme680_spi_write (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len); 274 | 275 | #define lsb_msb_to_type(t,b,o) (t)(((t)b[o+1] << 8) | b[o]) 276 | #define lsb_to_type(t,b,o) (t)(b[o]) 277 | 278 | bme680_sensor_t* bme680_init_sensor(uint8_t bus, uint8_t addr, uint8_t cs) 279 | 280 | { 281 | bme680_sensor_t* dev; 282 | 283 | if ((dev = malloc (sizeof(bme680_sensor_t))) == NULL) 284 | return NULL; 285 | 286 | // init sensor data structure 287 | dev->bus = bus; 288 | dev->addr = addr; 289 | dev->cs = cs; 290 | dev->meas_started = false; 291 | dev->meas_status = 0; 292 | dev->settings.ambient_temperature = 0; 293 | dev->settings.osr_temperature = osr_none; 294 | dev->settings.osr_pressure = osr_none; 295 | dev->settings.osr_humidity = osr_none; 296 | dev->settings.filter_size = iir_size_0; 297 | dev->settings.heater_profile = BME680_HEATER_NOT_USED; 298 | memset(dev->settings.heater_temperature, 0, sizeof(uint16_t)*10); 299 | memset(dev->settings.heater_duration, 0, sizeof(uint16_t)*10); 300 | 301 | // if addr==0 then SPI is used and has to be initialized 302 | if (!addr && !spi_device_init (bus, cs)) 303 | { 304 | error_dev ("Could not initialize SPI interface.", __FUNCTION__, dev); 305 | free (dev); 306 | return NULL; 307 | } 308 | 309 | // reset the sensor 310 | if (!bme680_reset(dev)) 311 | { 312 | error_dev ("Could not reset the sensor device.", __FUNCTION__, dev); 313 | free (dev); 314 | return NULL; 315 | } 316 | 317 | // check availability of the sensor 318 | if (!bme680_is_available (dev)) 319 | { 320 | error_dev ("Sensor is not available.", __FUNCTION__, dev); 321 | free (dev); 322 | return NULL; 323 | } 324 | 325 | uint8_t buf[BME680_CDM_SIZE]; 326 | 327 | // read all calibration parameters from sensor 328 | if (bme680_read_reg(dev, BME680_REG_CD1_ADDR, buf+BME680_CDM_OFF1, BME680_REG_CD1_LEN) && 329 | bme680_read_reg(dev, BME680_REG_CD2_ADDR, buf+BME680_CDM_OFF2, BME680_REG_CD2_LEN) && 330 | bme680_read_reg(dev, BME680_REG_CD3_ADDR, buf+BME680_CDM_OFF3, BME680_REG_CD3_LEN)) 331 | { 332 | dev->calib_data.par_t1 = lsb_msb_to_type (uint16_t, buf, BME680_CDM_T1); 333 | dev->calib_data.par_t2 = lsb_msb_to_type ( int16_t, buf, BME680_CDM_T2); 334 | dev->calib_data.par_t3 = lsb_to_type ( int8_t, buf, BME680_CDM_T3); 335 | 336 | // pressure compensation parameters 337 | dev->calib_data.par_p1 = lsb_msb_to_type (uint16_t, buf, BME680_CDM_P1); 338 | dev->calib_data.par_p2 = lsb_msb_to_type ( int16_t, buf, BME680_CDM_P2); 339 | dev->calib_data.par_p3 = lsb_to_type ( int8_t, buf, BME680_CDM_P3); 340 | dev->calib_data.par_p4 = lsb_msb_to_type ( int16_t, buf, BME680_CDM_P4); 341 | dev->calib_data.par_p5 = lsb_msb_to_type ( int16_t, buf, BME680_CDM_P5); 342 | dev->calib_data.par_p6 = lsb_to_type ( int8_t, buf, BME680_CDM_P6); 343 | dev->calib_data.par_p7 = lsb_to_type ( int8_t, buf, BME680_CDM_P7); 344 | dev->calib_data.par_p8 = lsb_msb_to_type ( int16_t, buf, BME680_CDM_P8); 345 | dev->calib_data.par_p9 = lsb_msb_to_type ( int16_t, buf, BME680_CDM_P9); 346 | dev->calib_data.par_p10 = lsb_to_type ( uint8_t, buf, BME680_CDM_P10); 347 | 348 | // humidity compensation parameters 349 | dev->calib_data.par_h1 = (uint16_t)(((uint16_t)buf[BME680_CDM_H1+1] << 4) | 350 | (buf[BME680_CDM_H1] & 0x0F)); 351 | dev->calib_data.par_h2 = (uint16_t)(((uint16_t)buf[BME680_CDM_H2] << 4) | 352 | (buf[BME680_CDM_H2+1] >> 4)); 353 | dev->calib_data.par_h3 = lsb_to_type ( int8_t, buf, BME680_CDM_H3); 354 | dev->calib_data.par_h4 = lsb_to_type ( int8_t, buf, BME680_CDM_H4); 355 | dev->calib_data.par_h5 = lsb_to_type ( int8_t, buf, BME680_CDM_H5); 356 | dev->calib_data.par_h6 = lsb_to_type ( uint8_t, buf, BME680_CDM_H6); 357 | dev->calib_data.par_h7 = lsb_to_type ( int8_t, buf, BME680_CDM_H7); 358 | 359 | // gas sensor compensation parameters 360 | dev->calib_data.par_gh1 = lsb_to_type ( int8_t, buf, BME680_CDM_GH1); 361 | dev->calib_data.par_gh2 = lsb_msb_to_type ( int16_t, buf, BME680_CDM_GH2); 362 | dev->calib_data.par_gh3 = lsb_to_type ( int8_t, buf, BME680_CDM_GH3); 363 | 364 | dev->calib_data.res_heat_range = (lsb_to_type (uint8_t, buf ,BME680_CDM_RHR) & 365 | BME680_RHR_BITS) >> 366 | BME680_RHR_SHIFT; 367 | dev->calib_data.res_heat_val = (lsb_to_type ( int8_t, buf, BME680_CDM_RHV)); 368 | dev->calib_data.range_sw_err = (lsb_to_type ( int8_t, buf, BME680_CDM_RSWE) & 369 | BME680_RSWE_BITS) >> 370 | BME680_RSWE_SHIFT; 371 | } 372 | else 373 | { 374 | error_dev ("Could not read in calibration parameters.", __FUNCTION__, dev); 375 | dev->error_code |= BME680_READ_CALIB_DATA_FAILED; 376 | free (dev); 377 | return NULL; 378 | 379 | } 380 | 381 | // Set the default temperature, pressure and humidity settings 382 | if (!bme680_set_oversampling_rates (dev, osr_1x, osr_1x, osr_1x) || 383 | !bme680_set_filter_size (dev, iir_size_3)) 384 | { 385 | error_dev ("Could not configure default sensor settings for TPH.", __FUNCTION__, dev); 386 | free (dev); 387 | return NULL; 388 | } 389 | 390 | // Set ambient temperature of sensor to default value (25 degree C) 391 | dev->settings.ambient_temperature = 25; 392 | 393 | // Set heater default profile 0 to 320 degree Celcius for 150 ms 394 | if (!bme680_set_heater_profile (dev, 0, 320, 150)) 395 | { 396 | error_dev ("Could not configure default heater profile settings.", __FUNCTION__, dev); 397 | free (dev); 398 | return NULL; 399 | } 400 | 401 | if (!bme680_use_heater_profile (dev, 0)) 402 | { 403 | error_dev ("Could not configure default heater profile.", __FUNCTION__, dev); 404 | free (dev); 405 | return NULL; 406 | } 407 | 408 | return dev; 409 | } 410 | 411 | bool bme680_force_measurement (bme680_sensor_t* dev) 412 | { 413 | if (!dev) return false; 414 | 415 | dev->error_code = BME680_OK; 416 | 417 | // return remaining time when measurement is already running 418 | if (dev->meas_started) 419 | { 420 | debug_dev ("Measurement is already running.", __FUNCTION__, dev); 421 | dev->error_code |= BME680_MEAS_ALREADY_RUNNING; 422 | return false; 423 | } 424 | 425 | // Set the power mode to forced mode to trigger one TPHG measurement cycle 426 | if (!bme680_set_mode(dev, BME680_FORCED_MODE)) 427 | { 428 | error_dev ("Could not set forced mode to start TPHG measurement cycle.", __FUNCTION__, dev); 429 | dev->error_code |= BME680_FORCE_MODE_FAILED; 430 | return false; 431 | } 432 | 433 | dev->meas_started = true; 434 | dev->meas_status = 0; 435 | 436 | debug_dev ("Started measurement at %.3f.", __FUNCTION__, dev, 437 | (double)sdk_system_get_time()*1e-3); 438 | 439 | return true; 440 | } 441 | 442 | 443 | /** 444 | * @brief Estimate the measuerment duration in ms 445 | * 446 | * Timing formulas extracted from BME280 datasheet and test in some 447 | * experiments. They represent the maximum measurement duration. 448 | * 449 | * @return estimated measurument duration in RTOS ticks or -1 on error 450 | */ 451 | uint32_t bme680_get_measurement_duration (const bme680_sensor_t *dev) 452 | { 453 | if (!dev) return 0; 454 | 455 | int32_t duration = 0; /* Calculate in us */ 456 | 457 | // wake up duration from sleep into forced mode 458 | duration += 1250; 459 | 460 | // THP cycle duration which consumes 1963 µs for each measurement at maximum 461 | if (dev->settings.osr_temperature) duration += (1 << (dev->settings.osr_temperature-1)) * 2300; 462 | if (dev->settings.osr_pressure ) duration += (1 << (dev->settings.osr_pressure-1)) * 2300 + 575; 463 | if (dev->settings.osr_humidity ) duration += (1 << (dev->settings.osr_humidity-1)) * 2300 + 575; 464 | 465 | // if gas measurement is used 466 | if (dev->settings.heater_profile != BME680_HEATER_NOT_USED && 467 | dev->settings.heater_duration[dev->settings.heater_profile] && 468 | dev->settings.heater_temperature[dev->settings.heater_profile]) 469 | { 470 | // gas heating time 471 | duration += dev->settings.heater_duration[dev->settings.heater_profile]*1000; 472 | // gas measurement duration; 473 | duration += 2300 + 575; 474 | } 475 | 476 | // round up to next ms (1 us ... 1000 us => 1 ms) 477 | duration += 999; 478 | duration /= 1000; 479 | 480 | // some ms tolerance 481 | duration += 5; 482 | 483 | // ceil to next integer value that is divisible by portTICK_PERIOD_MS and 484 | // compute RTOS ticks (1 ... portTICK_PERIOD_MS = 1 tick) 485 | duration = (duration + portTICK_PERIOD_MS-1) / portTICK_PERIOD_MS; 486 | 487 | // Since first RTOS tick can be shorter than the half of defined tick period, 488 | // the delay caused by vTaskDelay(duration) might be 1 or 2 ms shorter than 489 | // computed duration in rare cases. Since the duration is computed for maximum 490 | // and not for the typical durations and therefore tends to be too long, this 491 | // should not be a problem. Therefore, only one additional tick used. 492 | return duration + 1; 493 | } 494 | 495 | 496 | bool bme680_is_measuring (bme680_sensor_t* dev) 497 | { 498 | if (!dev) return false; 499 | 500 | dev->error_code = BME680_OK; 501 | 502 | // if measurement wasn't started, it is of course not measuring 503 | if (!dev->meas_started) 504 | { 505 | dev->error_code |= BME680_MEAS_NOT_RUNNING; 506 | return false; 507 | } 508 | 509 | uint8_t raw[2]; 510 | 511 | // read maesurment status from sensor 512 | if (!bme680_read_reg(dev, BME680_REG_MEAS_STATUS_0, raw, 2)) 513 | { 514 | error_dev ("Could not read measurement status from sensor.", __FUNCTION__, dev); 515 | return false; 516 | } 517 | 518 | dev->meas_status = raw[0]; 519 | 520 | // test whether measuring bit is set 521 | return (dev->meas_status & BME680_MEASURING_BITS); 522 | } 523 | 524 | 525 | bool bme680_get_results_fixed (bme680_sensor_t* dev, bme680_values_fixed_t* results) 526 | { 527 | if (!dev || !results) return false; 528 | 529 | dev->error_code = BME680_OK; 530 | 531 | // fill data structure with invalid values 532 | results->temperature = INT16_MIN; 533 | results->pressure = 0; 534 | results->humidity = 0; 535 | results->gas_resistance = 0; 536 | 537 | bme680_raw_data_t raw; 538 | 539 | if (!bme680_get_raw_data(dev, &raw)) 540 | // return invalid values 541 | return false; 542 | 543 | // use compensation algorithms to compute sensor values in fixed point format 544 | 545 | if (dev->settings.osr_temperature) 546 | results->temperature = bme680_convert_temperature (dev, raw.temperature); 547 | 548 | if (dev->settings.osr_pressure) 549 | results->pressure = bme680_convert_pressure (dev, raw.pressure); 550 | 551 | if (dev->settings.osr_humidity) 552 | results->humidity = bme680_convert_humidity (dev, raw.humidity); 553 | 554 | if (dev->settings.heater_profile != BME680_HEATER_NOT_USED) 555 | { 556 | // convert gas only if raw data are valid and heater was stable 557 | if (raw.gas_valid && raw.heater_stable) 558 | results->gas_resistance = bme680_convert_gas (dev, raw.gas_resistance, 559 | raw.gas_range); 560 | else if (!raw.gas_valid) 561 | dev->error_code = BME680_MEAS_GAS_NOT_VALID; 562 | else 563 | dev->error_code = BME680_HEATER_NOT_STABLE; 564 | } 565 | 566 | debug_dev ("Fixed point sensor valus - %d ms: %d/100 C, %d/1000 Percent, %d Pascal, %d Ohm", 567 | __FUNCTION__, dev, sdk_system_get_time (), 568 | results->temperature, 569 | results->humidity, 570 | results->pressure, 571 | results->gas_resistance); 572 | 573 | return true; 574 | } 575 | 576 | 577 | bool bme680_get_results_float (bme680_sensor_t* dev, bme680_values_float_t* results) 578 | { 579 | if (!dev || !results) return false; 580 | 581 | bme680_values_fixed_t fixed; 582 | 583 | if (!bme680_get_results_fixed (dev, &fixed)) 584 | return false; 585 | 586 | results->temperature = fixed.temperature / 100.0f; 587 | results->pressure = fixed.pressure / 100.0f; 588 | results->humidity = fixed.humidity / 1000.0f; 589 | results->gas_resistance = fixed.gas_resistance; 590 | 591 | return true; 592 | } 593 | 594 | 595 | bool bme680_measure_fixed (bme680_sensor_t* dev, bme680_values_fixed_t* results) 596 | { 597 | int32_t duration = bme680_force_measurement (dev); 598 | 599 | if (duration == BME680_NOK) 600 | return false; // measurment couldn't be started 601 | 602 | else if (duration > 0) // wait for results 603 | vTaskDelay (duration); 604 | 605 | return bme680_get_results_fixed (dev, results); 606 | } 607 | 608 | 609 | bool bme680_measure_float (bme680_sensor_t* dev, bme680_values_float_t* results) 610 | { 611 | int32_t duration = bme680_force_measurement (dev); 612 | 613 | if (duration == BME680_NOK) 614 | return false; // measurment couldn't be started 615 | 616 | else if (duration > 0) // wait for results 617 | vTaskDelay (duration); 618 | 619 | return bme680_get_results_float (dev, results); 620 | } 621 | 622 | 623 | 624 | #define bme_set_reg_bit(byte, bitname, bit) ( (byte & ~bitname##_BITS) | \ 625 | ((bit << bitname##_SHIFT) & bitname##_BITS) ) 626 | #define bme_get_reg_bit(byte, bitname) ( (byte & bitname##_BITS) >> bitname##_SHIFT ) 627 | 628 | bool bme680_set_oversampling_rates (bme680_sensor_t* dev, 629 | bme680_oversampling_rate_t ost, 630 | bme680_oversampling_rate_t osp, 631 | bme680_oversampling_rate_t osh) 632 | { 633 | if (!dev) return false; 634 | 635 | dev->error_code = BME680_OK; 636 | 637 | bool ost_changed = dev->settings.osr_temperature != ost; 638 | bool osp_changed = dev->settings.osr_pressure != osp; 639 | bool osh_changed = dev->settings.osr_humidity != osh; 640 | 641 | if (!ost_changed && !osp_changed && !osh_changed) 642 | return true; 643 | 644 | // Set the temperature, pressure and humidity oversampling 645 | dev->settings.osr_temperature = ost; 646 | dev->settings.osr_pressure = osp; 647 | dev->settings.osr_humidity = osh; 648 | 649 | uint8_t reg; 650 | 651 | if (ost_changed || osp_changed) 652 | { 653 | // read the current register value 654 | if (!bme680_read_reg(dev, BME680_REG_CTRL_MEAS, ®, 1)) 655 | return false; 656 | 657 | // set changed bit values 658 | if (ost_changed) reg = bme_set_reg_bit (reg, BME680_OSR_T, ost); 659 | if (osp_changed) reg = bme_set_reg_bit (reg, BME680_OSR_P, osp); 660 | 661 | // write back the new register value 662 | if (!bme680_write_reg(dev, BME680_REG_CTRL_MEAS, ®, 1)) 663 | return false; 664 | } 665 | 666 | if (osh_changed) 667 | { 668 | // read the current register value 669 | if (!bme680_read_reg(dev, BME680_REG_CTRL_HUM, ®, 1)) 670 | return false; 671 | 672 | // set changed bit value 673 | reg = bme_set_reg_bit (reg, BME680_OSR_H, osh); 674 | 675 | // write back the new register value 676 | if (!bme680_write_reg(dev, BME680_REG_CTRL_HUM, ®, 1)) 677 | return false; 678 | } 679 | 680 | debug_dev ("Setting oversampling rates done: osrt=%d osp=%d osrh=%d", 681 | __FUNCTION__, dev, 682 | dev->settings.osr_temperature, 683 | dev->settings.osr_pressure, 684 | dev->settings.osr_humidity); 685 | 686 | return true; 687 | } 688 | 689 | 690 | bool bme680_set_filter_size(bme680_sensor_t* dev, bme680_filter_size_t size) 691 | { 692 | if (!dev) return false; 693 | 694 | dev->error_code = BME680_OK; 695 | 696 | bool size_changed = dev->settings.filter_size != size; 697 | 698 | if (!size_changed) return true; 699 | 700 | /* Set the temperature, pressure and humidity settings */ 701 | dev->settings.filter_size = size; 702 | 703 | uint8_t reg; 704 | 705 | // read the current register value 706 | if (!bme680_read_reg(dev, BME680_REG_CONFIG, ®, 1)) 707 | return false; 708 | 709 | // set changed bit value 710 | reg = bme_set_reg_bit (reg, BME680_FILTER, size); 711 | 712 | // write back the new register value 713 | if (!bme680_write_reg(dev, BME680_REG_CONFIG, ®, 1)) 714 | return false; 715 | 716 | debug_dev ("Setting filter size done: size=%d", __FUNCTION__, dev, 717 | dev->settings.filter_size); 718 | 719 | return true; 720 | } 721 | 722 | bool bme680_set_heater_profile (bme680_sensor_t* dev, uint8_t profile, 723 | uint16_t temperature, uint16_t duration) 724 | { 725 | if (!dev) return false; 726 | 727 | if (profile > BME680_HEATER_PROFILES-1) 728 | { 729 | error_dev("Wrong heater profile id %d.", __FUNCTION__, dev, profile); 730 | dev->error_code = BME680_WRONG_HEAT_PROFILE; 731 | return false; 732 | } 733 | 734 | dev->error_code = BME680_OK; 735 | 736 | bool temperature_changed = dev->settings.heater_temperature[profile] != temperature; 737 | bool duration_changed = dev->settings.heater_duration[profile] != duration; 738 | 739 | if (!temperature_changed && !duration_changed) 740 | return true; 741 | 742 | // set external gas sensor configuration 743 | dev->settings.heater_temperature[profile] = temperature; // degree Celsius 744 | dev->settings.heater_duration [profile] = duration; // milliseconds 745 | 746 | // compute internal gas sensor configuration parameters 747 | uint8_t heat_dur = bme680_heater_duration(duration); // internal duration value 748 | uint8_t heat_res = bme680_heater_resistance(dev, temperature); // internal temperature value 749 | 750 | // set internal gas sensor configuration parameters if changed 751 | if (temperature_changed && 752 | !bme680_write_reg(dev, BME680_REG_RES_HEAT_BASE+profile, &heat_res, 1)) 753 | return false; 754 | 755 | if (duration_changed && 756 | !bme680_write_reg(dev, BME680_REG_GAS_WAIT_BASE+profile, &heat_dur, 1)) 757 | return false; 758 | 759 | debug_dev ("Setting heater profile %d done: temperature=%d duration=%d " 760 | "heater_resistance=%02x heater_duration=%02x", 761 | __FUNCTION__, dev, profile, 762 | dev->settings.heater_temperature[profile], 763 | dev->settings.heater_duration[profile], 764 | heat_dur, heat_res); 765 | 766 | return true; 767 | } 768 | 769 | bool bme680_use_heater_profile (bme680_sensor_t* dev, int8_t profile) 770 | { 771 | if (!dev) return false; 772 | 773 | if (profile != BME680_HEATER_NOT_USED && (profile < 0 || profile > BME680_HEATER_PROFILES-1)) 774 | { 775 | error_dev("Wrong heater profile id %d.", __FUNCTION__, dev, profile); 776 | dev->error_code = BME680_WRONG_HEAT_PROFILE; 777 | return false; 778 | } 779 | 780 | if (dev->settings.heater_profile == profile) 781 | return false; 782 | 783 | dev->settings.heater_profile = profile; 784 | 785 | uint8_t reg = 0; // set 786 | // set active profile 787 | reg = bme_set_reg_bit (reg, BME680_NB_CONV, profile != BME680_HEATER_NOT_USED ? profile : 0); 788 | 789 | // enable or disable gas measurement 790 | reg = bme_set_reg_bit (reg, BME680_RUN_GAS, (profile != BME680_HEATER_NOT_USED && 791 | dev->settings.heater_temperature[profile] && 792 | dev->settings.heater_duration[profile])); 793 | 794 | if (!bme680_write_reg(dev, BME680_REG_CTRL_GAS_1, ®, 1)) 795 | return false; 796 | 797 | return true; 798 | } 799 | 800 | 801 | bool bme680_set_ambient_temperature (bme680_sensor_t* dev, int16_t ambient) 802 | { 803 | if (!dev) return false; 804 | 805 | dev->error_code = BME680_OK; 806 | 807 | bool ambient_changed = dev->settings.ambient_temperature != ambient; 808 | 809 | if (!ambient_changed) 810 | return true; 811 | 812 | // set ambient temperature configuration 813 | dev->settings.ambient_temperature = ambient; // degree Celsius 814 | 815 | // update all valid heater profiles 816 | uint8_t data[10]; 817 | for (int i = 0; i < BME680_HEATER_PROFILES; i++) 818 | { 819 | data[i] = dev->settings.heater_temperature[i] ? 820 | bme680_heater_resistance(dev, dev->settings.heater_temperature[i]) : 0; 821 | } 822 | if (!bme680_write_reg(dev, BME680_REG_RES_HEAT_BASE, data, 10)) 823 | return false; 824 | 825 | debug_dev ("Setting heater ambient temperature done: ambient=%d", 826 | __FUNCTION__, dev, dev->settings.ambient_temperature); 827 | 828 | return true; 829 | } 830 | 831 | bool bme680_set_mode (bme680_sensor_t *dev, uint8_t mode) 832 | { 833 | if (!dev) return false; 834 | 835 | dev->error_code = BME680_OK; 836 | 837 | uint8_t reg; 838 | 839 | if (!bme680_read_reg(dev, BME680_REG_CTRL_MEAS, ®, 1)) 840 | return false; 841 | 842 | reg = bme_set_reg_bit (reg, BME680_MODE, mode); 843 | 844 | if (!bme680_write_reg(dev, BME680_REG_CTRL_MEAS, ®, 1)) 845 | return false; 846 | 847 | return true; 848 | } 849 | 850 | 851 | /** Functions for internal use only */ 852 | 853 | /** 854 | * @brief Check the chip ID to test whether sensor is available 855 | */ 856 | static bool bme680_is_available (bme680_sensor_t* dev) 857 | { 858 | uint8_t chip_id; 859 | 860 | if (!dev) return false; 861 | 862 | dev->error_code = BME680_OK; 863 | 864 | if (!bme680_read_reg (dev, BME680_REG_ID, &chip_id, 1)) 865 | return false; 866 | 867 | if (chip_id != 0x61) 868 | { 869 | error_dev ("Chip id %02x is wrong, should be 0x61.", __FUNCTION__, dev, chip_id); 870 | dev->error_code = BME680_WRONG_CHIP_ID; 871 | return false; 872 | } 873 | 874 | return true; 875 | } 876 | 877 | 878 | static bool bme680_reset (bme680_sensor_t* dev) 879 | { 880 | if (!dev) return false; 881 | 882 | dev->error_code = BME680_OK; 883 | 884 | uint8_t reg = BME680_RESET_CMD; 885 | 886 | // send reset command 887 | if (!bme680_write_reg(dev, BME680_REG_RESET, ®, 1)) 888 | return false; 889 | 890 | // wait the time the sensor needs for reset 891 | bme680_delay_ms (BME680_RESET_PERIOD); 892 | 893 | // check whether the sensor is reachable again 894 | if (!bme680_read_reg(dev, BME680_REG_STATUS, ®, 1)) 895 | { 896 | dev->error_code = BME680_RESET_CMD_FAILED; 897 | return false; 898 | } 899 | 900 | return true; 901 | } 902 | 903 | 904 | /** 905 | * @brief Calculate temperature from raw temperature value 906 | * @ref BME280 datasheet, page 50 907 | */ 908 | static int16_t bme680_convert_temperature (bme680_sensor_t *dev, uint32_t raw_temperature) 909 | { 910 | if (!dev) return 0; 911 | 912 | bme680_calib_data_t* cd = &dev->calib_data; 913 | 914 | int64_t var1; 915 | int64_t var2; 916 | int16_t temperature; 917 | 918 | var1 = ((((raw_temperature >> 3) - ((int32_t)cd->par_t1 << 1))) * 919 | ((int32_t)cd->par_t2)) >> 11; 920 | var2 = (((((raw_temperature >> 4) - ((int32_t)cd->par_t1)) * 921 | ((raw_temperature >> 4) - ((int32_t)cd->par_t1))) >> 12) * 922 | ((int32_t)cd->par_t3)) >> 14; 923 | cd->t_fine = (int32_t)(var1 + var2); 924 | temperature = (cd->t_fine * 5 + 128) >> 8; 925 | 926 | return temperature; 927 | } 928 | 929 | 930 | /** 931 | * @brief Calculate pressure from raw pressure value 932 | * @copyright Copyright (C) 2017 - 2018 Bosch Sensortec GmbH 933 | * 934 | * The algorithm was extracted from the original Bosch Sensortec BME680 driver 935 | * published as open source. Divisions and multiplications by potences of 2 936 | * were replaced by shift operations for effeciency reasons. 937 | * 938 | * @ref [BME680_diver](https://github.com/BoschSensortec/BME680_driver) 939 | * @ref BME280 datasheet, page 50 940 | */ 941 | static uint32_t bme680_convert_pressure (bme680_sensor_t *dev, uint32_t raw_pressure) 942 | { 943 | if (!dev) return 0; 944 | 945 | bme680_calib_data_t* cd = &dev->calib_data; 946 | 947 | int32_t var1; 948 | int32_t var2; 949 | int32_t var3; 950 | int32_t var4; 951 | int32_t pressure; 952 | 953 | var1 = (((int32_t) cd->t_fine) >> 1) - 64000; 954 | var2 = ((((var1 >> 2) * (var1 >> 2)) >> 11) * (int32_t) cd->par_p6) >> 2; 955 | var2 = ((var2) * (int32_t) cd->par_p6) >> 2; 956 | var2 = var2 + ((var1 * (int32_t)cd->par_p5) << 1); 957 | var2 = (var2 >> 2) + ((int32_t) cd->par_p4 << 16); 958 | var1 = (((var1 >> 2) * (var1 >> 2)) >> 13); 959 | var1 = (((var1) * ((int32_t) cd->par_p3 << 5)) >> 3) + (((int32_t) cd->par_p2 * var1) >> 1); 960 | var1 = var1 >> 18; 961 | var1 = ((32768 + var1) * (int32_t) cd->par_p1) >> 15; 962 | pressure = 1048576 - raw_pressure; 963 | pressure = (int32_t)((pressure - (var2 >> 12)) * ((uint32_t)3125)); 964 | var4 = (1 << 31); 965 | pressure = (pressure >= var4) ? (( pressure / (uint32_t) var1) << 1) 966 | : ((pressure << 1) / (uint32_t) var1); 967 | var1 = ((int32_t) cd->par_p9 * (int32_t) (((pressure >> 3) * (pressure >> 3)) >> 13)) >> 12; 968 | var2 = ((int32_t)(pressure >> 2) * (int32_t) cd->par_p8) >> 13; 969 | var3 = ((int32_t)(pressure >> 8) * (int32_t)(pressure >> 8) 970 | * (int32_t)(pressure >> 8) 971 | * (int32_t)cd->par_p10) >> 17; 972 | pressure = (int32_t)(pressure) + ((var1 + var2 + var3 + ((int32_t)cd->par_p7 << 7)) >> 4); 973 | 974 | return (uint32_t) pressure; 975 | } 976 | 977 | /** 978 | * @brief Calculate humidty from raw humidity data 979 | * @copyright Copyright (C) 2017 - 2018 Bosch Sensortec GmbH 980 | * 981 | * The algorithm was extracted from the original Bosch Sensortec BME680 driver 982 | * published as open source. Divisions and multiplications by potences of 2 983 | * were replaced by shift operations for effeciency reasons. 984 | * 985 | * @ref [BME680_diver](https://github.com/BoschSensortec/BME680_driver) 986 | */ 987 | static uint32_t bme680_convert_humidity (bme680_sensor_t *dev, uint16_t raw_humidity) 988 | { 989 | if (!dev) return 0; 990 | 991 | bme680_calib_data_t* cd = &dev->calib_data; 992 | 993 | int32_t var1; 994 | int32_t var2; 995 | int32_t var3; 996 | int32_t var4; 997 | int32_t var5; 998 | int32_t var6; 999 | int32_t temp_scaled; 1000 | int32_t humidity; 1001 | 1002 | temp_scaled = (((int32_t) cd->t_fine * 5) + 128) >> 8; 1003 | var1 = (int32_t) (raw_humidity - ((int32_t) ((int32_t) cd->par_h1 << 4))) - 1004 | (((temp_scaled * (int32_t) cd->par_h3) / ((int32_t) 100)) >> 1); 1005 | var2 = ((int32_t) cd->par_h2 * 1006 | (((temp_scaled * (int32_t) cd->par_h4) / ((int32_t) 100)) + 1007 | (((temp_scaled * ((temp_scaled * (int32_t) cd->par_h5) / ((int32_t) 100))) >> 6) / 1008 | ((int32_t) 100)) + (int32_t) (1 << 14))) >> 10; 1009 | var3 = var1 * var2; 1010 | var4 = (int32_t) cd->par_h6 << 7; 1011 | var4 = ((var4) + ((temp_scaled * (int32_t) cd->par_h7) / ((int32_t) 100))) >> 4; 1012 | var5 = ((var3 >> 14) * (var3 >> 14)) >> 10; 1013 | var6 = (var4 * var5) >> 1; 1014 | humidity = (((var3 + var6) >> 10) * ((int32_t) 1000)) >> 12; 1015 | 1016 | if (humidity > 100000) /* Cap at 100%rH */ 1017 | humidity = 100000; 1018 | else if (humidity < 0) 1019 | humidity = 0; 1020 | 1021 | return (uint32_t) humidity; 1022 | } 1023 | 1024 | 1025 | /** 1026 | * @brief Lookup table for gas resitance computation 1027 | * @ref BME680 datasheet, page 19 1028 | */ 1029 | static float lookup_table[16][2] = { // const1, const2 // gas_range 1030 | { 1.0 , 8000000.0 }, // 0 1031 | { 1.0 , 4000000.0 }, // 1 1032 | { 1.0 , 2000000.0 }, // 2 1033 | { 1.0 , 1000000.0 }, // 3 1034 | { 1.0 , 499500.4995 }, // 4 1035 | { 0.99 , 248262.1648 }, // 5 1036 | { 1.0 , 125000.0 }, // 6 1037 | { 0.992, 63004.03226 }, // 7 1038 | { 1.0 , 31281.28128 }, // 8 1039 | { 1.0 , 15625.0 }, // 9 1040 | { 0.998, 7812.5 }, // 10 1041 | { 0.995, 3906.25 }, // 11 1042 | { 1.0 , 1953.125 }, // 12 1043 | { 0.99 , 976.5625 }, // 13 1044 | { 1.0 , 488.28125 }, // 14 1045 | { 1.0 , 244.140625 } // 15 1046 | }; 1047 | 1048 | /** 1049 | * @brief Calculate gas resistance from raw gas resitance value and gas range 1050 | * @ref BME680 datasheet 1051 | */ 1052 | static uint32_t bme680_convert_gas (bme680_sensor_t *dev, uint16_t gas, uint8_t gas_range) 1053 | { 1054 | if (!dev) return 0; 1055 | 1056 | bme680_calib_data_t* cd = &dev->calib_data; 1057 | 1058 | float var1 = (1340.0 + 5.0 * cd->range_sw_err) * lookup_table[gas_range][0]; 1059 | return var1 * lookup_table[gas_range][1] / (gas - 512.0 + var1); 1060 | } 1061 | 1062 | #define msb_lsb_xlsb_to_20bit(t,b,o) (t)((t) b[o] << 12 | (t) b[o+1] << 4 | b[o+2] >> 4) 1063 | #define msb_lsb_to_type(t,b,o) (t)(((t)b[o] << 8) | b[o+1]) 1064 | 1065 | #define BME680_RAW_P_OFF BME680_REG_PRESS_MSB_0-BME680_REG_MEAS_STATUS_0 1066 | #define BME680_RAW_T_OFF (BME680_RAW_P_OFF + BME680_REG_TEMP_MSB_0 - BME680_REG_PRESS_MSB_0) 1067 | #define BME680_RAW_H_OFF (BME680_RAW_T_OFF + BME680_REG_HUM_MSB_0 - BME680_REG_TEMP_MSB_0) 1068 | #define BME680_RAW_G_OFF (BME680_RAW_H_OFF + BME680_REG_GAS_R_MSB_0 - BME680_REG_HUM_MSB_0) 1069 | 1070 | static bool bme680_get_raw_data(bme680_sensor_t *dev, bme680_raw_data_t* raw_data) 1071 | { 1072 | if (!dev || !raw_data) return false; 1073 | 1074 | dev->error_code = BME680_OK; 1075 | 1076 | if (!dev->meas_started) 1077 | { 1078 | error_dev ("Measurement was not started.", __FUNCTION__, dev); 1079 | dev->error_code = BME680_MEAS_NOT_RUNNING; 1080 | return false; 1081 | } 1082 | 1083 | uint8_t raw[BME680_REG_RAW_DATA_LEN] = { 0 }; 1084 | 1085 | if (!(dev->meas_status & BME680_NEW_DATA_BITS)) 1086 | { 1087 | // read maesurment status from sensor 1088 | if (!bme680_read_reg(dev, BME680_REG_MEAS_STATUS_0, raw, 2)) 1089 | { 1090 | error_dev ("Could not read measurement status from sensor.", __FUNCTION__, dev); 1091 | return false; 1092 | } 1093 | 1094 | // test whether there are new data 1095 | dev->meas_status = raw[0]; 1096 | if (dev->meas_status & BME680_MEASURING_BITS && 1097 | !(dev->meas_status & BME680_NEW_DATA_BITS)) 1098 | { 1099 | debug_dev ("Measurement is still running.", __FUNCTION__, dev); 1100 | dev->error_code = BME680_MEAS_STILL_RUNNING; 1101 | return false; 1102 | } 1103 | else if (!(dev->meas_status & BME680_NEW_DATA_BITS)) 1104 | { 1105 | debug_dev ("No new data.", __FUNCTION__, dev); 1106 | dev->error_code = BME680_NO_NEW_DATA; 1107 | return false; 1108 | } 1109 | } 1110 | 1111 | dev->meas_started = false; 1112 | raw_data->gas_index = (dev->meas_status & BME680_GAS_MEAS_INDEX_BITS); 1113 | 1114 | // if there are new data, read raw data from sensor 1115 | 1116 | if (!bme680_read_reg(dev, BME680_REG_RAW_DATA_0, raw, BME680_REG_RAW_DATA_LEN)) 1117 | { 1118 | error_dev ("Could not read raw data from sensor.", __FUNCTION__, dev); 1119 | return false; 1120 | } 1121 | 1122 | raw_data->gas_valid = bme_get_reg_bit(raw[BME680_RAW_G_OFF+1],BME680_GAS_VALID); 1123 | raw_data->heater_stable = bme_get_reg_bit(raw[BME680_RAW_G_OFF+1],BME680_HEAT_STAB_R); 1124 | 1125 | raw_data->temperature = msb_lsb_xlsb_to_20bit (uint32_t, raw, BME680_RAW_T_OFF); 1126 | raw_data->pressure = msb_lsb_xlsb_to_20bit (uint32_t, raw, BME680_RAW_P_OFF); 1127 | raw_data->humidity = msb_lsb_to_type (uint16_t, raw, BME680_RAW_H_OFF); 1128 | raw_data->gas_resistance = ((uint16_t)raw[BME680_RAW_G_OFF] << 2) | raw[BME680_RAW_G_OFF+1] >> 6; 1129 | raw_data->gas_range = raw[BME680_RAW_G_OFF+1] & BME680_GAS_RANGE_R_BITS; 1130 | 1131 | /* 1132 | // These data are not documented and it is not really clear when they are filled 1133 | if (!bme680_read_reg(dev, BME680_REG_MEAS_STATUS_1, raw, BME680_REG_RAW_DATA_LEN)) 1134 | { 1135 | error_dev ("Could not read raw data from sensor.", __FUNCTION__, dev); 1136 | return false; 1137 | } 1138 | 1139 | if (!bme680_read_reg(dev, BME680_REG_MEAS_STATUS_2, raw, BME680_REG_RAW_DATA_LEN)) 1140 | { 1141 | error_dev ("Could not read raw data from sensor.", __FUNCTION__, dev); 1142 | return false; 1143 | } 1144 | */ 1145 | debug ("Raw data: %d %d %d %d %d",__FUNCTION__, 1146 | raw_data->temperature, raw_data->pressure, 1147 | raw_data->humidity, raw_data->gas_resistance, raw_data->gas_range); 1148 | 1149 | return true; 1150 | } 1151 | 1152 | 1153 | /** 1154 | * @brief Calculate internal duration representation 1155 | * 1156 | * Durations are internally representes as one byte 1157 | * 1158 | * duration = value<5:0> * multiplier<7:6> 1159 | * 1160 | * where the multiplier is 1, 4, 16, or 64. Maximum duration is therefore 1161 | * 64*64 = 4032 ms. The function takes a real world duration value given 1162 | * in milliseconds and computes the internal representation. 1163 | * 1164 | * @ref Datasheet 1165 | */ 1166 | static uint8_t bme680_heater_duration (uint16_t duration) 1167 | { 1168 | uint8_t multiplier = 0; 1169 | 1170 | while (duration > 63) 1171 | { 1172 | duration = duration / 4; 1173 | multiplier++; 1174 | } 1175 | return (uint8_t) (duration | (multiplier << 6)); 1176 | } 1177 | 1178 | 1179 | /** 1180 | * @brief Calculate internal heater resistance value from real temperature. 1181 | * 1182 | * @ref Datasheet of BME680 1183 | */ 1184 | static uint8_t bme680_heater_resistance (const bme680_sensor_t *dev, uint16_t temp) 1185 | { 1186 | if (!dev) return 0; 1187 | 1188 | if (temp < BME680_HEATER_TEMP_MIN) 1189 | temp = BME680_HEATER_TEMP_MIN; 1190 | else if (temp > BME680_HEATER_TEMP_MAX) 1191 | temp = BME680_HEATER_TEMP_MAX; 1192 | 1193 | const bme680_calib_data_t* cd = &dev->calib_data; 1194 | 1195 | // from datasheet 1196 | double var1; 1197 | double var2; 1198 | double var3; 1199 | double var4; 1200 | double var5; 1201 | uint8_t res_heat_x; 1202 | 1203 | var1 = ((double)cd->par_gh1 / 16.0) + 49.0; 1204 | var2 = (((double)cd->par_gh2 / 32768.0) * 0.0005) + 0.00235; 1205 | var3 = (double)cd->par_gh3 / 1024.0; 1206 | var4 = var1 * (1.0 + (var2 * (double) temp)); 1207 | var5 = var4 + (var3 * (double)dev->settings.ambient_temperature); 1208 | res_heat_x = (uint8_t)(3.4 * ((var5 * (4.0 / (4.0 + (double)cd->res_heat_range)) * 1209 | (1.0/(1.0 + ((double)cd->res_heat_val * 0.002)))) - 25)); 1210 | return res_heat_x; 1211 | 1212 | } 1213 | 1214 | 1215 | static void bme680_delay_ms(uint32_t period) 1216 | { 1217 | uint32_t start_time = sdk_system_get_time () / 1000; 1218 | 1219 | vTaskDelay((period + portTICK_PERIOD_MS-1) / portTICK_PERIOD_MS); 1220 | 1221 | while (sdk_system_get_time()/1000 - start_time < period) 1222 | vTaskDelay (1); 1223 | } 1224 | 1225 | 1226 | static bool bme680_read_reg(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len) 1227 | { 1228 | if (!dev || !data) return false; 1229 | 1230 | return (dev->addr) ? bme680_i2c_read (dev, reg, data, len) 1231 | : bme680_spi_read (dev, reg, data, len); 1232 | } 1233 | 1234 | 1235 | static bool bme680_write_reg(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len) 1236 | { 1237 | if (!dev || !data) return false; 1238 | 1239 | return (dev->addr) ? bme680_i2c_write (dev, reg, data, len) 1240 | : bme680_spi_write (dev, reg, data, len); 1241 | } 1242 | 1243 | #define BME680_SPI_BUF_SIZE 64 // SPI register data buffer size of ESP866 1244 | 1245 | #define BME680_REG_SWITCH_MEM_PAGE BME680_REG_STATUS 1246 | #define BME680_BIT_SWITCH_MEM_PAGE_0 0x00 1247 | #define BME680_BIT_SWITCH_MEM_PAGE_1 0x10 1248 | 1249 | static bool bme680_spi_set_mem_page (bme680_sensor_t* dev, uint8_t reg) 1250 | { 1251 | // mem pages (reg 0x00 .. 0x7f = 1, reg 0x80 ... 0xff = 0 1252 | uint8_t mem_page = (reg < 0x80) ? BME680_BIT_SWITCH_MEM_PAGE_1 1253 | : BME680_BIT_SWITCH_MEM_PAGE_0; 1254 | 1255 | debug_dev ("Set mem page for register %02x to %d.", __FUNCTION__, dev, reg, mem_page); 1256 | 1257 | if (!bme680_spi_write (dev, BME680_REG_SWITCH_MEM_PAGE, &mem_page, 1)) 1258 | { 1259 | dev->error_code |= BME680_SPI_SET_PAGE_FAILED; 1260 | return false; 1261 | } 1262 | // sdk_os_delay_us (100); 1263 | return true; 1264 | } 1265 | 1266 | static bool bme680_spi_read(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len) 1267 | { 1268 | if (!dev || !data) return false; 1269 | 1270 | if (len >= BME680_SPI_BUF_SIZE) 1271 | { 1272 | dev->error_code |= BME680_SPI_BUFFER_OVERFLOW; 1273 | error_dev ("Error on read from SPI slave on bus 1. Tried to transfer " 1274 | "more than %d byte in one read operation.", 1275 | __FUNCTION__, dev, BME680_SPI_BUF_SIZE); 1276 | return false; 1277 | } 1278 | 1279 | // set mem page first 1280 | if (!bme680_spi_set_mem_page (dev, reg)) 1281 | { 1282 | error_dev ("Error on read from SPI slave on bus 1. Could not set mem page.", 1283 | __FUNCTION__, dev); 1284 | return false; 1285 | } 1286 | 1287 | reg &= 0x7f; 1288 | reg |= 0x80; 1289 | 1290 | static uint8_t mosi[BME680_SPI_BUF_SIZE]; 1291 | static uint8_t miso[BME680_SPI_BUF_SIZE]; 1292 | 1293 | memset (mosi, 0xff, BME680_SPI_BUF_SIZE); 1294 | memset (miso, 0xff, BME680_SPI_BUF_SIZE); 1295 | 1296 | mosi[0] = reg; 1297 | 1298 | if (!spi_transfer_pf (dev->bus, dev->cs, mosi, miso, len+1)) 1299 | { 1300 | error_dev ("Could not read data from SPI", __FUNCTION__, dev); 1301 | dev->error_code |= BME680_SPI_READ_FAILED; 1302 | return false; 1303 | } 1304 | // shift data one by left, first byte received while sending register address is invalid 1305 | for (int i=0; i < len; i++) 1306 | data[i] = miso[i+1]; 1307 | 1308 | #ifdef BME680_DEBUG_LEVEL_2 1309 | printf("BME680 %s: read the following bytes: ", __FUNCTION__); 1310 | printf("%0x ", reg); 1311 | for (int i=0; i < len; i++) 1312 | printf("%0x ", data[i]); 1313 | printf("\n"); 1314 | #endif 1315 | 1316 | return true; 1317 | } 1318 | 1319 | 1320 | static bool bme680_spi_write(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len) 1321 | { 1322 | if (!dev || !data) return false; 1323 | 1324 | static uint8_t mosi[BME680_SPI_BUF_SIZE]; 1325 | 1326 | if (len >= BME680_SPI_BUF_SIZE) 1327 | { 1328 | dev->error_code |= BME680_SPI_BUFFER_OVERFLOW; 1329 | error_dev ("Error on write to SPI slave on bus 1. Tried to transfer more" 1330 | "than %d byte in one write operation.", __FUNCTION__, dev, BME680_SPI_BUF_SIZE); 1331 | 1332 | return false; 1333 | } 1334 | 1335 | // set mem page first if not mem page register is used 1336 | if (reg != BME680_REG_STATUS && !bme680_spi_set_mem_page (dev, reg)) 1337 | { 1338 | error_dev ("Error on write from SPI slave on bus 1. Could not set mem page.", 1339 | __FUNCTION__, dev); 1340 | return false; 1341 | } 1342 | 1343 | reg &= 0x7f; 1344 | 1345 | // first byte in output is the register address 1346 | mosi[0] = reg; 1347 | 1348 | // shift data one byte right, first byte in output is the register address 1349 | for (int i = 0; i < len; i++) 1350 | mosi[i+1] = data[i]; 1351 | 1352 | #ifdef BME680_DEBUG_LEVEL_2 1353 | printf("BME680 %s: Write the following bytes: ", __FUNCTION__); 1354 | for (int i = 0; i < len+1; i++) 1355 | printf("%0x ", mosi[i]); 1356 | printf("\n"); 1357 | #endif 1358 | 1359 | if (!spi_transfer_pf (dev->bus, dev->cs, mosi, NULL, len+1)) 1360 | { 1361 | error_dev ("Could not write data to SPI.", __FUNCTION__, dev); 1362 | dev->error_code |= BME680_SPI_WRITE_FAILED; 1363 | return false; 1364 | } 1365 | 1366 | return true; 1367 | } 1368 | 1369 | 1370 | static bool bme680_i2c_read(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len) 1371 | { 1372 | if (!dev || !data) return false; 1373 | 1374 | debug_dev ("Read %d byte from i2c slave register %02x.", __FUNCTION__, dev, len, reg); 1375 | 1376 | int result = i2c_slave_read(dev->bus, dev->addr, ®, data, len); 1377 | 1378 | if (result) 1379 | { 1380 | dev->error_code |= (result == -EBUSY) ? BME680_I2C_BUSY : BME680_I2C_READ_FAILED; 1381 | error_dev ("Error %d on read %d byte from I2C slave register %02x.", 1382 | __FUNCTION__, dev, result, len, reg); 1383 | return false; 1384 | } 1385 | 1386 | # ifdef BME680_DEBUG_LEVEL_2 1387 | printf("BME680 %s: Read following bytes: ", __FUNCTION__); 1388 | printf("%0x: ", reg); 1389 | for (int i=0; i < len; i++) 1390 | printf("%0x ", data[i]); 1391 | printf("\n"); 1392 | # endif 1393 | 1394 | return true; 1395 | } 1396 | 1397 | 1398 | static bool bme680_i2c_write(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len) 1399 | { 1400 | if (!dev || !data) return false; 1401 | 1402 | debug_dev ("Write %d byte to i2c slave register %02x.", __FUNCTION__, dev, len, reg); 1403 | 1404 | int result = i2c_slave_write(dev->bus, dev->addr, ®, data, len); 1405 | 1406 | if (result) 1407 | { 1408 | dev->error_code |= (result == -EBUSY) ? BME680_I2C_BUSY : BME680_I2C_WRITE_FAILED; 1409 | error_dev ("Error %d on write %d byte to i2c slave register %02x.", 1410 | __FUNCTION__, dev, result, len, reg); 1411 | return false; 1412 | } 1413 | 1414 | # ifdef BME680_DEBUG_LEVEL_2 1415 | printf("BME680 %s: Wrote the following bytes: ", __FUNCTION__); 1416 | printf("%0x: ", reg); 1417 | for (int i=0; i < len; i++) 1418 | printf("%0x ", data[i]); 1419 | printf("\n"); 1420 | # endif 1421 | 1422 | return true; 1423 | } 1424 | --------------------------------------------------------------------------------