Driver for the brand new Bosch BME680 sensor added
I have written a driver for Bosch Sensortec's BME680 sensor. This sensor integrates temperature, pressure, humidity and gas sensors in a single unit.
This commit is contained in:
		
							parent
							
								
									0448887473
								
							
						
					
					
						commit
						c420d82c42
					
				
					 7 changed files with 3340 additions and 0 deletions
				
			
		
							
								
								
									
										341
									
								
								extras/bme680/README.md
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										341
									
								
								extras/bme680/README.md
									
										
									
									
									
										Normal file
									
								
							|  | @ -0,0 +1,341 @@ | |||
| # Driver for BME680 digital temperature and humidity sensor | ||||
| 
 | ||||
| This driver is written for usage with the ESP8266 and FreeRTOS ([esp-open-rtos](https://github.com/SuperHouse/esp-open-rtos) and [esp-open-rtos-driver-i2c](https://github.com/kanflo/esp-open-rtos-driver-i2c)). | ||||
| 
 | ||||
| Please note:  | ||||
| 
 | ||||
| 1. The driver supports multiple sensors that are connected either to I2C as well as SPI. | ||||
| 
 | ||||
| 2. Due to the complexity of the sensor output value compputation based on many calibration parameters, the original Bosch Sensortec BME680 driver that is released as open source [https://github.com/BoschSensortec/BME680_driver] is integrated for internal use. Please note the license of this part, which is an extended BSD license and can be found in each of that source files. | ||||
| 
 | ||||
| ## About the sensor | ||||
| 
 | ||||
| BME680 is an low power environmental sensor that integrates a temperature, a pressure, a humidity and a gas sensor in only one unit. It can be connected to controller using either I2C or SPI. | ||||
| 
 | ||||
| ### Sensor modes | ||||
| 
 | ||||
| BME680 can operate in two different low-level power modes, the *sleep mode* and the *forced mode*. | ||||
| 
 | ||||
| #### Sleep mode | ||||
| 
 | ||||
| This mode is the default mode. The sensor starts automatically in this mode after power-up sequence. In this mode it does not perform any measurement and therefore just consumes 0.15 μA. | ||||
| 
 | ||||
| #### Forced Mode | ||||
| 
 | ||||
| Using the mode switch command, the sensor switches from sleep mode into the forced mode. In this mode, temperature, pressure, humidity and gas measurements are performed sequentially exactly once. Such a measurement cycle is also called TPHG (Temperature, Pressure, Humidity and Gas).  | ||||
| 
 | ||||
| Each of these measurements can be influenced, activated or skipped separately via the sensor settings, see section **Measurement settings**. | ||||
| 
 | ||||
| ### Measurement settings | ||||
| 
 | ||||
| The sensor allows to change different measurement parameters. | ||||
| 
 | ||||
| #### Oversampling rates | ||||
| 
 | ||||
| For temperature, pressure, and humidity measurements, it is possible by the user task to individually define different over-sampling rates for each of these measurements. Possible over-sampling 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. | ||||
| 
 | ||||
| #### IIR Filter | ||||
| 
 | ||||
| The sensor 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. | ||||
| 
 | ||||
| The filter can optionally be used for pressure and temperature data that are subject to many short-term changes. Humidity and gas inside the sensor does not fluctuate rapidly and does not require such a low pass filtering. | ||||
| 
 | ||||
| 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. | ||||
| 
 | ||||
| #### Heater profile | ||||
| 
 | ||||
| For gas measurement the sensor integrates a heater. The paremeters for this heater are defined by a heater profile. Such a heater profile consists of a temperature setting point (the target temperature) and the heating duration.  | ||||
| 
 | ||||
| Even though the sensor supports up to 10 different such profiles at them same time, only one profile is used by the driver for simplicity reasons. The temperature setting point and the heating duration of this one profile can be defined by the user task. Default values used by the driver are 320 degree Celcius as target temperature and 150 ms heating duration.  | ||||
| 
 | ||||
| According to the datasheet, target temperatures of 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. | ||||
| 
 | ||||
| If heating duration is 0 ms, the gas measurement is skipped and output values become invalid. | ||||
| 
 | ||||
| ### Communication interfaces | ||||
| 
 | ||||
| The sensor can be connected using I2C or SPI. The driver support both communication interfaces. | ||||
| 
 | ||||
| The I2C interface supports the Standard, Fast and High Speed modes up to 3.4 Mbps. It is possible to connect multiple BME680 with two different I2C slave addresses (0x76 and 0x77) to one I2C bus or with same I2C addresses to different I2C busses. | ||||
| 
 | ||||
| The SPI interface allows clock rates up to 10 MHz and SPI modes '00' (CPOL=CPHA=0) and '11' (CPOL=CPHA=1). | ||||
| 
 | ||||
| Interface selection is done automatically using the 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. | ||||
| 
 | ||||
| ## How the driver works | ||||
| 
 | ||||
| To avoid blocking of user tasks during measurements due to their duration, separate tasks running in background are used to realize the measurements. These background tasks are created implicitly when a user task calls function *bme680_create_sensor* for each connected BME680 sensor. The background tasks realize the measurement procedures which are executed periodically at a rate that can be defined by the user for each sensor separately using function *bme680_set_measurement_period* (default period is 1000 ms). | ||||
| 
 | ||||
| ### Measurement method | ||||
| 
 | ||||
| The driver triggers a measurement cycle using functions of the original Bosch Sensortec BME680 driver, which has been released as open source [https://github.com/BoschSensortec/BME680_driver] and is integrated for internal use. These functions call up recall functions of the driver which implement the communication with the sensor. | ||||
| 
 | ||||
| The duration of a THPG measuring cycle can vary from a few milliseconds to a half a second, depending on which measurements of the THPG measuring cycle are activated and the measurement settings such as the oversampling rate and heating profile as well as sensor value processing parameters such as the IIR filter size. | ||||
| 
 | ||||
| Therefore, the measurement period should be not less than 1 second. | ||||
| 
 | ||||
| ### Measured data | ||||
| 
 | ||||
| At each measurement, *actual sensor values* for temperature, pressure, humidity as well as gas are determined as floating point values from the measured data sets. Temperature is given in °C, pressure in hectopascals, Humidity in percent and gas is given in Ohm representing the resistance of sensor's gas sensitive layer. | ||||
| 
 | ||||
| If average value computation is enabled (default), the background task also computes successively at each measurement the *average sensor values* based on these *actual sensor values* using the exponential moving average  | ||||
| 
 | ||||
|     Average[k] = W * Actual + (1-W) * Average [k-1] | ||||
| 
 | ||||
| where coefficient W represents the degree of weighting decrease, a constant smoothing factor between 0 and 1. A higher W discounts older observations faster. The coefficient W (smoothing factor) can be defined by the user task using function *bme680_set_average_weight*. The default value of W is 0.2. The average value computation can be enabled or disabled using function *bme680_enable_average_computation*. | ||||
| 
 | ||||
| If average computation is disabled, *average sensor values* correspond to the *actual sensor values*. | ||||
| 
 | ||||
| ### Getting results. | ||||
| 
 | ||||
| As soon as a measurement is completed, the actual sensor values * and * average sensor values * can be read by user tasks. There are two ways to do this: | ||||
| 
 | ||||
| - define a callback function or  | ||||
| - call the function * bme680_get_values * explicitly. | ||||
| 
 | ||||
| #### Using callback function | ||||
| 
 | ||||
| For each connected BME680 sensor, the user task can register a callback function using function *bme680_set_callback_function*. If a callback function is registered, it is called by the background task after each measurement to pass *actual sensor values* and *average sensor values* to user tasks. Thus, the user gets the results of the measurements automatically with same rate as the periodic measurements are executed. | ||||
| 
 | ||||
| Using the callback function is the easiest way to get the results. | ||||
| 
 | ||||
| #### Using function bme680_get_values | ||||
| 
 | ||||
| If no recall function is registered, the user task must call *bme680_get_values* to get the *current sensor values* and *average sensor values*. These values are stored in data structures of type *bme680_value_set_t*, which are passed as pointer parameters to the function. By NULL pointers for one of these parameters, the user task can decide which results are not interesting. | ||||
| 
 | ||||
| To ensure that the actual and average sensor values are up-to-date, the rate of periodic measurements realized by the background task should be at least equal to or higher than the rate of calling the function *bme680_get_values*. That is, the measurement period in the background task which is set by function *bme680_set_measurement_period* must be less than or equal to the rate of calling function *bme680_get_values*. | ||||
| 
 | ||||
| Please note: If gas measurement is activated, the measuring period should be at least 1 second. | ||||
| 
 | ||||
| ## Usage  | ||||
| 
 | ||||
| First, the hardware configuration has to be establisch. This can differ dependent on the communication interface and the number of sensors to be used. | ||||
| 
 | ||||
| ### Hardware configuration | ||||
| 
 | ||||
| First figure shows a possible configuration with only one I2C busses. | ||||
| 
 | ||||
| ``` | ||||
|  +------------------------+     +--------+ | ||||
|  | ESP8266  Bus 0         |     | BME680 | | ||||
|  |          GPIO 5 (SCL)  +---->+ SCL    | | ||||
|  |          GPIO 4 (SDA)  +-----+ SDA    | | ||||
|  |                        |     +--------+ | ||||
|  +------------------------+ | ||||
| ``` | ||||
| Next figure shows a possible configuration with two I2C busses. | ||||
| 
 | ||||
| ``` | ||||
|  +------------------------+     +----------+ | ||||
|  | ESP8266  Bus 0         |     | BME680_1 | | ||||
|  |          GPIO 5 (SCL)  ------> SCL      | | ||||
|  |          GPIO 4 (SDA)  ------- SDA      | | ||||
|  |                        |     +----------+ | ||||
|  |          Bus 1         |     | BME680_2 | | ||||
|  |          GPIO 12 (SCL) ------> SCL      | | ||||
|  |          GPIO 14 (SDA) ------- SDA      | | ||||
|  +------------------------+     +----------+ | ||||
| ``` | ||||
| 
 | ||||
| Last figure shows a possible configuration using SPI bus 1. | ||||
| 
 | ||||
|  +-------------------------+     +--------+ | ||||
|  | ESP8266  Bus 0          |     | BME680 | | ||||
|  |          GPIO 12 (MISO) <------ SDO    | | ||||
|  |          GPIO 13 (MOSI) >-----> SDA    | | ||||
|  |          GPIO 14 (SCK)  >-----> SCK    | | ||||
|  |          GPIO 2  (CS)   >-----> CS     | | ||||
|  +-------------------------+     +--------+ | ||||
| 
 | ||||
| Please note:  | ||||
| 
 | ||||
| 1. Since the system flash memory is connected to SPI bus 0, the sensor has to be connected to SPI bus 1.  | ||||
| 
 | ||||
| 2. GPIO15 used as CS signal of SPI bus 1 by default, does not work correctly together with BME680's signal. Therefore, the user has to specify another GPIO pin as CS signal when the sensor is created, e.g. GPIO2. | ||||
| 
 | ||||
| ### Communication interface dependent part | ||||
| 
 | ||||
| According to the hardware configuration, some constants should be defined, e.g. for | ||||
| only one I2C and the SPI. | ||||
| 
 | ||||
| ``` | ||||
| #define I2C_BUS         0 | ||||
| #define I2C_SCL_PIN     GPIO_ID_PIN((5)) | ||||
| #define I2C_SDA_PIN     GPIO_ID_PIN((4)) | ||||
| 
 | ||||
| #define BME680_ADDR1    0x76 | ||||
| #define BME680_ADDR2    0x77 // default | ||||
| 
 | ||||
| #define SPI_BUS         1 | ||||
| #define SPI_CS_GPIO     2   // GPIO 15, the default CS of SPI bus 1, can't be used | ||||
| ``` | ||||
| Only in case of I2C, the I2C driver has to initialized before it can be used. This is not neccessary for SPI. | ||||
| 
 | ||||
| ``` | ||||
| ... | ||||
| i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ_100K)) | ||||
| ``` | ||||
| 
 | ||||
| Next, the BME680 driver itself has to be initialized using function *bme680_init*. This is independent on the communication interface. | ||||
| 
 | ||||
| ``` | ||||
| bme680_init_driver(); | ||||
| ``` | ||||
| 
 | ||||
| If BME680 driver initialization was successful, function *bme680_create_sensor* has to be called for each sensor to initialize the sensor connected to a certain bus with given slave address, to check its availability and to start the background task for measurements. | ||||
| 
 | ||||
| In the case of I2C interface, this call looks like following. The last parameter is the SPI CS signal pin is ignored in case of I2C. | ||||
| 
 | ||||
| ``` | ||||
| sensor = bme680_create_sensor (I2C_BUS, BME680_ADDR2, 0); | ||||
| ``` | ||||
| 
 | ||||
| For SPI the call looks like this. The second parameter is the I2C slave address, that is invalid. It is used by function *bme680_create_sensor* to determine the communication infertace to be used. In cas of SPI, the GPIO for CS signal has to be specified. | ||||
| 
 | ||||
| ``` | ||||
|     sensor = bme680_create_sensor (SPI_BUS, 0, SPI_CS_GPIO); | ||||
| ``` | ||||
| 
 | ||||
| On success this function returns the *ID* of a sensor descriptor between 0 and *BME680_MAX_SENSORS* or -1 otherwise. This *ID* is used to identify the sensor in all other functions used later. | ||||
| 
 | ||||
| The remaining part of the software is independent on the communication interface. | ||||
| 
 | ||||
| If you want to use a callback function defined like following to get the measurement results | ||||
| 
 | ||||
| ``` | ||||
| static void my_callback_function (uint32_t sensor,  | ||||
|                                   bme680_value_set_t actual,  | ||||
|                                   bme680_value_set_t average) | ||||
| { | ||||
|   ... | ||||
| } | ||||
| ``` | ||||
| 
 | ||||
| You have to register this callback function using *bme680_set_callback_function*. | ||||
| 
 | ||||
| ``` | ||||
| bme680_set_callback_function (sensor, &my_callback_function); | ||||
| ``` | ||||
| 
 | ||||
| Optionally, you could wish to set some measurement parameters. For details see the section **Measurement settings** above, the header file of the driver **bme680_driver.h**, and of course the datasheet of the sensor. | ||||
| 
 | ||||
| ``` | ||||
| // Change the period of measurements (default 1000 ms) to 500 ms. | ||||
| bme680_set_measurement_period (sensor, 500); | ||||
|      | ||||
| // Changes the oversampling rates (default os_1x) to 4x oversampling for | ||||
| // temperature and 2x oversampling for pressure. Humidity measurement is | ||||
| // skipped. | ||||
| bme680_set_oversampling_rates(sensor, os_4x, os_2x, none); | ||||
|      | ||||
| // Change the IIR filter size (default iir_size_3) for temperature and  | ||||
| // and pressure to 7. | ||||
| bme680_set_filter_size(sensor, iir_size_7); | ||||
| 
 | ||||
| // Change the heaeter profile (default 320 degree Celcius for 150 ms) to | ||||
| // 200 degree Celcius for 100 ms. | ||||
| bme680_set_heater_profile (sensor, 200, 100); | ||||
| ``` | ||||
| 
 | ||||
| All functions return a boolean that allows effective error handling. | ||||
| 
 | ||||
| ## Full Example for one sensor connected to I2C bus | ||||
| 
 | ||||
| ``` | ||||
| 
 | ||||
| #include "espressif/esp_common.h" | ||||
| #include "esp/uart.h" | ||||
| #include "i2c/i2c.h" | ||||
| 
 | ||||
| // include BME680 driver | ||||
| #include "bme680/bme680_drv.h" | ||||
| 
 | ||||
| // define I2C interfaces at which BME680 sensors can be connected | ||||
| #define I2C_BUS       0 | ||||
| #define I2C_SCL_PIN   GPIO_ID_PIN((5)) | ||||
| #define I2C_SDA_PIN   GPIO_ID_PIN((4)) | ||||
| 
 | ||||
| #define BME680_ADDR1    0x76 | ||||
| #define BME680_ADDR2    0x77 // default | ||||
| 
 | ||||
| static uint32_t sensor; | ||||
| 
 | ||||
| /** | ||||
|  * Everything you need is a callback function that can handle | ||||
|  * callbacks from the background measurement task of the | ||||
|  * BME680 driver. This function is called periodically | ||||
|  * and delivers the actual and average sensor value sets for  | ||||
|  * given sensor. | ||||
|  */ | ||||
| 
 | ||||
| static void my_callback_function (uint32_t sensor,  | ||||
|                                   bme680_value_set_t actual,  | ||||
|                                   bme680_value_set_t average) | ||||
| { | ||||
|     printf("%.3f Sensor %d: %.2f (%.2f) C, %.2f (%.2f) Percent, %.2f (%.2f) hPa, %.2f (%.2f) Ohm\n",  | ||||
|            (double)sdk_system_get_time()*1e-3, sensor,  | ||||
|             actual.temperature, average.temperature, | ||||
|             actual.humidity, average.humidity, | ||||
|             actual.pressure, average.pressure, | ||||
|             actual.gas, average.gas); | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| void user_init(void) | ||||
| { | ||||
|     // Set UART Parameter | ||||
|     uart_set_baud(0, 115200); | ||||
|     // Give the UART some time to settle | ||||
|     sdk_os_delay_us(500); | ||||
|      | ||||
|     /** Please note:  | ||||
|       * Function *bme680_create_sensor* returns a value greater or equal 0 | ||||
|       * on succes, all other *bme680_* functions return true on success. Using | ||||
|       * these return values, you could realize an error handling. Error  | ||||
|       * handling is not realized in this example due to readability reasons. | ||||
|       */ | ||||
|      | ||||
|     /** -- MANDATORY PART -- */ | ||||
|      | ||||
|     // Init all I2C bus interfaces at which BME680 sensors are connected | ||||
|     i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ_100K); | ||||
| 
 | ||||
|     // Init BME680 driver itself. | ||||
|     bme680_init_driver(); | ||||
| 
 | ||||
|     // Create the sensor with slave address 0x77 (BME680_ADDR2) connected to | ||||
|     // I2C bus 0 (I2C_BUS_1). Parameter *cs* is ignored in case of I2C. | ||||
|     sensor = bme680_create_sensor (I2C_BUS, BME680_ADDR2, 0); | ||||
| 
 | ||||
|     // Register the callback function to get measurement results. | ||||
|     bme680_set_callback_function (sensor, &my_callback_function); | ||||
| 
 | ||||
|     // That's it. | ||||
| 
 | ||||
|     /** -- OPTIONAL PART -- */ | ||||
| 
 | ||||
|     // Change the period of measurements (default 1000 ms) to 500 ms. | ||||
|     bme680_set_measurement_period (sensor, 500); | ||||
|      | ||||
|     // Changes the oversampling rates (default os_1x) to 4x oversampling for | ||||
|     // temperature and 2x oversampling for pressure. Humidity measurement is | ||||
|     // skipped. | ||||
|     bme680_set_oversampling_rates(sensor, os_4x, os_2x, none); | ||||
|      | ||||
|     // Change the IIR filter size (default iir_size_3) for temperature and  | ||||
|     // and pressure to 7. | ||||
|     bme680_set_filter_size(sensor, iir_size_7); | ||||
| 
 | ||||
|     // Change the heaeter profile (default 320 degree Celcius for 150 ms) to | ||||
|     // 200 degree Celcius for 100 ms. | ||||
|     bme680_set_heater_profile (sensor, 200, 100); | ||||
| } | ||||
| ``` | ||||
| 
 | ||||
| ## Further Examples | ||||
| 
 | ||||
| For further examples see [examples directory](../../examples/bme680/README.md) | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										1105
									
								
								extras/bme680/bme680.c
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										1105
									
								
								extras/bme680/bme680.c
									
										
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load diff
											
										
									
								
							
							
								
								
									
										225
									
								
								extras/bme680/bme680.h
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										225
									
								
								extras/bme680/bme680.h
									
										
									
									
									
										Normal file
									
								
							|  | @ -0,0 +1,225 @@ | |||
| /**
 | ||||
|  * Copyright (C) 2017 - 2018 Bosch Sensortec GmbH | ||||
|  * | ||||
|  * Redistribution and use in source and binary forms, with or without | ||||
|  * modification, are permitted provided that the following conditions are met: | ||||
|  * | ||||
|  * Redistributions of source code must retain the above copyright | ||||
|  * notice, this list of conditions and the following disclaimer. | ||||
|  * | ||||
|  * Redistributions in binary form must reproduce the above copyright | ||||
|  * notice, this list of conditions and the following disclaimer in the | ||||
|  * documentation and/or other materials provided with the distribution. | ||||
|  * | ||||
|  * Neither the name of the copyright holder nor the names of the | ||||
|  * contributors may be used to endorse or promote products derived from | ||||
|  * this software without specific prior written permission. | ||||
|  * | ||||
|  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND | ||||
|  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR | ||||
|  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED | ||||
|  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE | ||||
|  * DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER | ||||
|  * OR CONTRIBUTORS BE LIABLE FOR ANY | ||||
|  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, | ||||
|  * OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO, | ||||
|  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; | ||||
|  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) | ||||
|  * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, | ||||
|  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT | ||||
|  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||||
|  * ANY WAY OUT OF THE USE OF THIS | ||||
|  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE | ||||
|  * | ||||
|  * The information provided is believed to be accurate and reliable. | ||||
|  * The copyright holder assumes no responsibility | ||||
|  * for the consequences of use | ||||
|  * of such information nor for any infringement of patents or | ||||
|  * other rights of third parties which may result from its use. | ||||
|  * No license is granted by implication or otherwise under any patent or | ||||
|  * patent rights of the copyright holder. | ||||
|  * | ||||
|  * @file	bme680.h | ||||
|  * @date	5 Jul 2017 | ||||
|  * @version	3.5.1 | ||||
|  * @brief | ||||
|  * | ||||
|  */ | ||||
| /*! @file bme680.h
 | ||||
|  @brief Sensor driver for BME680 sensor */ | ||||
| /*!
 | ||||
|  * @defgroup BME680 SENSOR API | ||||
|  * @{*/ | ||||
| #ifndef BME680_H_ | ||||
| #define BME680_H_ | ||||
| 
 | ||||
| /*! CPP guard */ | ||||
| #ifdef __cplusplus | ||||
| extern "C" | ||||
| { | ||||
| #endif | ||||
| 
 | ||||
| /* Header includes */ | ||||
| #include "bme680_defs.h" | ||||
| 
 | ||||
| /* function prototype declarations */ | ||||
| /*!
 | ||||
|  *  @brief This API is the entry point. | ||||
|  *  It reads the chip-id and calibration data from the sensor. | ||||
|  * | ||||
|  *  @param[in,out] dev : Structure instance of bme680_dev | ||||
|  * | ||||
|  *  @return Result of API execution status | ||||
|  *  @retval zero -> Success / +ve value -> Warning / -ve value -> Error | ||||
|  */ | ||||
| int8_t bme680_init(struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API writes the given data to the register address | ||||
|  * of the sensor. | ||||
|  * | ||||
|  * @param[in] reg_addr : Register address from where the data to be written. | ||||
|  * @param[in] reg_data : Pointer to data buffer which is to be written | ||||
|  * in the sensor. | ||||
|  * @param[in] len : No of bytes of data to write.. | ||||
|  * @param[in] dev : Structure instance of bme680_dev. | ||||
|  * | ||||
|  * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error | ||||
|  */ | ||||
| int8_t bme680_set_regs(const uint8_t *reg_addr, const uint8_t *reg_data, uint8_t len, struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API reads the data from the given register address of the sensor. | ||||
|  * | ||||
|  * @param[in] reg_addr : Register address from where the data to be read | ||||
|  * @param[out] reg_data : Pointer to data buffer to store the read data. | ||||
|  * @param[in] len : No of bytes of data to be read. | ||||
|  * @param[in] dev : Structure instance of bme680_dev. | ||||
|  * | ||||
|  * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error | ||||
|  */ | ||||
| int8_t bme680_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint16_t len, struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API performs the soft reset of the sensor. | ||||
|  * | ||||
|  * @param[in] dev : Structure instance of bme680_dev. | ||||
|  * | ||||
|  * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error. | ||||
|  */ | ||||
| int8_t bme680_soft_reset(struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API is used to set the power mode of the sensor. | ||||
|  * | ||||
|  * @param[in] dev : Structure instance of bme680_dev | ||||
|  * @note : Pass the value to bme680_dev.power_mode structure variable. | ||||
|  * | ||||
|  *  value	|	mode | ||||
|  * -------------|------------------ | ||||
|  *	0x00	|	BME680_SLEEP_MODE | ||||
|  *	0x01	|	BME680_FORCED_MODE | ||||
|  * | ||||
|  * * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error | ||||
|  */ | ||||
| int8_t bme680_set_sensor_mode(struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API is used to get the power mode of the sensor. | ||||
|  * | ||||
|  * @param[in] dev : Structure instance of bme680_dev | ||||
|  * @note : bme680_dev.power_mode structure variable hold the power mode. | ||||
|  * | ||||
|  *  value	|	mode | ||||
|  * ---------|------------------ | ||||
|  *	0x00	|	BME680_SLEEP_MODE | ||||
|  *	0x01	|	BME680_FORCED_MODE | ||||
|  * | ||||
|  * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error | ||||
|  */ | ||||
| int8_t bme680_get_sensor_mode(struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API is used to set the profile duration of the sensor. | ||||
|  * | ||||
|  * @param[in] dev	   : Structure instance of bme680_dev. | ||||
|  * @param[in] duration : Duration of the measurement in ms. | ||||
|  * | ||||
|  * @return Nothing | ||||
|  */ | ||||
| void bme680_set_profile_dur(uint16_t duration, struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API is used to get the profile duration of the sensor. | ||||
|  * | ||||
|  * @param[in] dev	   : Structure instance of bme680_dev. | ||||
|  * @param[in] duration : Duration of the measurement in ms. | ||||
|  * | ||||
|  * @return Nothing | ||||
|  */ | ||||
| void bme680_get_profile_dur(uint16_t *duration, struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API reads the pressure, temperature and humidity and gas data | ||||
|  * from the sensor, compensates the data and store it in the bme680_data | ||||
|  * structure instance passed by the user. | ||||
|  * | ||||
|  * @param[out] data: Structure instance to hold the data. | ||||
|  * @param[in] dev : Structure instance of bme680_dev. | ||||
|  * | ||||
|  * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error | ||||
|  */ | ||||
| int8_t bme680_get_sensor_data(struct bme680_field_data *data, struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API is used to set the oversampling, filter and T,P,H, gas selection | ||||
|  * settings in the sensor. | ||||
|  * | ||||
|  * @param[in] dev : Structure instance of bme680_dev. | ||||
|  * @param[in] desired_settings : Variable used to select the settings which | ||||
|  * are to be set in the sensor. | ||||
|  * | ||||
|  *	 Macros			       |	Functionality | ||||
|  *-------------------------|---------------------------------------------- | ||||
|  *	BME680_OST_SEL		   |	To set temperature oversampling. | ||||
|  *	BME680_OSP_SEL		   |	To set pressure oversampling. | ||||
|  *	BME680_OSH_SEL		   |	To set humidity oversampling. | ||||
|  *	BME680_GAS_MEAS_SEL	   |	To set gas measurement setting. | ||||
|  *	BME680_FILTER_SEL	   |	To set filter setting. | ||||
|  *	BME680_HCNTRL_SEL	   |	To set humidity control setting. | ||||
|  *	BME680_RUN_GAS_SEL	   |	To set run gas setting. | ||||
|  *	BME680_NBCONV_SEL	   |	To set NB conversion setting. | ||||
|  *	BME680_GAS_SENSOR_SEL  |	To set all gas sensor related settings | ||||
|  * | ||||
|  * @note : Below are the macros to be used by the user for selecting the | ||||
|  * desired settings. User can do OR operation of these macros for configuring | ||||
|  * multiple settings. | ||||
|  * | ||||
|  * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error. | ||||
|  */ | ||||
| int8_t bme680_set_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief This API is used to get the oversampling, filter and T,P,H, gas selection | ||||
|  * settings in the sensor. | ||||
|  * | ||||
|  * @param[in] dev : Structure instance of bme680_dev. | ||||
|  * @param[in] desired_settings : Variable used to select the settings which | ||||
|  * are to be get from the sensor. | ||||
|  * | ||||
|  * @return Result of API execution status | ||||
|  * @retval zero -> Success / +ve value -> Warning / -ve value -> Error. | ||||
|  */ | ||||
| int8_t bme680_get_sensor_settings(uint16_t desired_settings, struct bme680_dev *dev); | ||||
| #ifdef __cplusplus | ||||
| } | ||||
| #endif /* End of CPP guard */ | ||||
| #endif /* BME680_H_ */ | ||||
| /** @}*/ | ||||
							
								
								
									
										529
									
								
								extras/bme680/bme680_defs.h
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										529
									
								
								extras/bme680/bme680_defs.h
									
										
									
									
									
										Normal file
									
								
							|  | @ -0,0 +1,529 @@ | |||
| /**
 | ||||
|  * Copyright (C) 2017 - 2018 Bosch Sensortec GmbH | ||||
|  * | ||||
|  * Redistribution and use in source and binary forms, with or without | ||||
|  * modification, are permitted provided that the following conditions are met: | ||||
|  * | ||||
|  * Redistributions of source code must retain the above copyright | ||||
|  * notice, this list of conditions and the following disclaimer. | ||||
|  * | ||||
|  * Redistributions in binary form must reproduce the above copyright | ||||
|  * notice, this list of conditions and the following disclaimer in the | ||||
|  * documentation and/or other materials provided with the distribution. | ||||
|  * | ||||
|  * Neither the name of the copyright holder nor the names of the | ||||
|  * contributors may be used to endorse or promote products derived from | ||||
|  * this software without specific prior written permission. | ||||
|  * | ||||
|  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND | ||||
|  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR | ||||
|  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED | ||||
|  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE | ||||
|  * DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER | ||||
|  * OR CONTRIBUTORS BE LIABLE FOR ANY | ||||
|  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, | ||||
|  * OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO, | ||||
|  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; | ||||
|  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) | ||||
|  * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, | ||||
|  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT | ||||
|  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||||
|  * ANY WAY OUT OF THE USE OF THIS | ||||
|  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE | ||||
|  * | ||||
|  * The information provided is believed to be accurate and reliable. | ||||
|  * The copyright holder assumes no responsibility | ||||
|  * for the consequences of use | ||||
|  * of such information nor for any infringement of patents or | ||||
|  * other rights of third parties which may result from its use. | ||||
|  * No license is granted by implication or otherwise under any patent or | ||||
|  * patent rights of the copyright holder. | ||||
|  * | ||||
|  * @file    bme680_defs.h | ||||
|  * @date    5 Jul 2017 | ||||
|  * @version 3.5.1 | ||||
|  * @brief | ||||
|  * | ||||
|  */ | ||||
| 
 | ||||
| /*! @file bme680_defs.h
 | ||||
|  @brief Sensor driver for BME680 sensor */ | ||||
| /*!
 | ||||
|  * @defgroup BME680 SENSOR API | ||||
|  * @brief | ||||
|  * @{*/ | ||||
| #ifndef BME680_DEFS_H_ | ||||
| #define BME680_DEFS_H_ | ||||
| 
 | ||||
| /********************************************************/ | ||||
| /* header includes */ | ||||
| #ifdef __KERNEL__ | ||||
| #include <linux/types.h> | ||||
| #else | ||||
| #include <stdint.h> | ||||
| #endif | ||||
| 
 | ||||
| #ifdef __KERNEL__ | ||||
| #if (LONG_MAX) > 0x7fffffff | ||||
| #define __have_long64   1 | ||||
| #elif (LONG_MAX) == 0x7fffffff | ||||
| #define __have_long32   1 | ||||
| #endif | ||||
| 
 | ||||
| #if !defined(UINT8_C) | ||||
| #define INT8_C(x)       x | ||||
| #if (INT_MAX) > 0x7f | ||||
| #define UINT8_C(x)      x | ||||
| #else | ||||
| #define UINT8_C(x)      x##U | ||||
| #endif | ||||
| #endif | ||||
| 
 | ||||
| #if !defined(UINT16_C) | ||||
| #define INT16_C(x)      x | ||||
| #if (INT_MAX) > 0x7fff | ||||
| #define UINT16_C(x)     x | ||||
| #else | ||||
| #define UINT16_C(x)     x##U | ||||
| #endif | ||||
| #endif | ||||
| 
 | ||||
| #if !defined(INT32_C) && !defined(UINT32_C) | ||||
| #if __have_long32 | ||||
| #define INT32_C(x)      x##L | ||||
| #define UINT32_C(x)     x##UL | ||||
| #else | ||||
| #define INT32_C(x)      x | ||||
| #define UINT32_C(x)     x##U | ||||
| #endif | ||||
| #endif | ||||
| 
 | ||||
| #if !defined(INT64_C) && !defined(UINT64_C) | ||||
| #if __have_long64 | ||||
| #define INT64_C(x)      x##L | ||||
| #define UINT64_C(x)     x##UL | ||||
| #else | ||||
| #define INT64_C(x)      x##LL | ||||
| #define UINT64_C(x)     x##ULL | ||||
| #endif | ||||
| #endif | ||||
| #endif | ||||
| /**@}*/ | ||||
| 
 | ||||
| /**\name C standard macros */ | ||||
| #ifndef NULL | ||||
| #ifdef __cplusplus | ||||
| #define NULL   0 | ||||
| #else | ||||
| #define NULL   ((void *) 0) | ||||
| #endif | ||||
| #endif | ||||
| 
 | ||||
| /** BME680 General config */ | ||||
| #define BME680_POLL_PERIOD_MS		UINT8_C(10) | ||||
| 
 | ||||
| /** BME680 I2C addresses */ | ||||
| #define BME680_I2C_ADDR_PRIMARY		UINT8_C(0x76) | ||||
| #define BME680_I2C_ADDR_SECONDARY	UINT8_C(0x77) | ||||
| 
 | ||||
| /** BME680 unique chip identifier */ | ||||
| #define BME680_CHIP_ID  UINT8_C(0x61) | ||||
| 
 | ||||
| /** BME680 coefficients related defines */ | ||||
| #define BME680_COEFF_SIZE		UINT8_C(0x41) | ||||
| #define BME680_COEFF_ADDR1_LEN		UINT8_C(25) | ||||
| #define BME680_COEFF_ADDR2_LEN		UINT8_C(16) | ||||
| 
 | ||||
| /** BME680 field_x related defines */ | ||||
| #define BME680_FIELD_LENGTH		UINT8_C(15) | ||||
| #define BME680_FIELD_ADDR_OFFSET	UINT8_C(17) | ||||
| 
 | ||||
| /** Soft reset command */ | ||||
| #define BME680_SOFT_RESET_CMD   UINT8_C(0xb6) | ||||
| 
 | ||||
| /** Error code definitions */ | ||||
| #define BME680_OK		INT8_C(0) | ||||
| /* Errors */ | ||||
| #define BME680_E_NULL_PTR		    INT8_C(-1) | ||||
| #define BME680_E_COM_FAIL		    INT8_C(-2) | ||||
| #define BME680_E_DEV_NOT_FOUND		INT8_C(-3) | ||||
| #define BME680_E_INVALID_LENGTH		INT8_C(-4) | ||||
| 
 | ||||
| /* Warnings */ | ||||
| #define BME680_W_DEFINE_PWR_MODE	INT8_C(1) | ||||
| #define BME680_W_NO_NEW_DATA        INT8_C(2) | ||||
| 
 | ||||
| /* Info's */ | ||||
| #define BME680_I_MIN_CORRECTION		UINT8_C(1) | ||||
| #define BME680_I_MAX_CORRECTION		UINT8_C(2) | ||||
| 
 | ||||
| /** Register map */ | ||||
| /** Other coefficient's address */ | ||||
| #define BME680_ADDR_RES_HEAT_VAL_ADDR	UINT8_C(0x00) | ||||
| #define BME680_ADDR_RES_HEAT_RANGE_ADDR	UINT8_C(0x02) | ||||
| #define BME680_ADDR_RANGE_SW_ERR_ADDR	UINT8_C(0x04) | ||||
| #define BME680_ADDR_SENS_CONF_START	UINT8_C(0x5A) | ||||
| #define BME680_ADDR_GAS_CONF_START	UINT8_C(0x64) | ||||
| 
 | ||||
| /** Field settings */ | ||||
| #define BME680_FIELD0_ADDR		UINT8_C(0x1d) | ||||
| 
 | ||||
| /** Heater settings */ | ||||
| #define BME680_RES_HEAT0_ADDR		UINT8_C(0x5a) | ||||
| #define BME680_GAS_WAIT0_ADDR		UINT8_C(0x64) | ||||
| 
 | ||||
| /** Sensor configuration registers */ | ||||
| #define BME680_CONF_HEAT_CTRL_ADDR		UINT8_C(0x70) | ||||
| #define BME680_CONF_ODR_RUN_GAS_NBC_ADDR	UINT8_C(0x71) | ||||
| #define BME680_CONF_OS_H_ADDR			UINT8_C(0x72) | ||||
| #define BME680_MEM_PAGE_ADDR			UINT8_C(0xf3) | ||||
| #define BME680_CONF_T_P_MODE_ADDR		UINT8_C(0x74) | ||||
| #define BME680_CONF_ODR_FILT_ADDR		UINT8_C(0x75) | ||||
| 
 | ||||
| /** Coefficient's address */ | ||||
| #define BME680_COEFF_ADDR1	UINT8_C(0x89) | ||||
| #define BME680_COEFF_ADDR2	UINT8_C(0xe1) | ||||
| 
 | ||||
| /** Chip identifier */ | ||||
| #define BME680_CHIP_ID_ADDR	UINT8_C(0xd0) | ||||
| 
 | ||||
| /** Soft reset register */ | ||||
| #define BME680_SOFT_RESET_ADDR		UINT8_C(0xe0) | ||||
| 
 | ||||
| /** Heater control settings */ | ||||
| #define BME680_ENABLE_HEATER		UINT8_C(0x00) | ||||
| #define BME680_DISABLE_HEATER		UINT8_C(0x08) | ||||
| 
 | ||||
| /** Gas measurement settings */ | ||||
| #define BME680_DISABLE_GAS_MEAS		UINT8_C(0x00) | ||||
| #define BME680_ENABLE_GAS_MEAS		UINT8_C(0x01) | ||||
| 
 | ||||
| /** Over-sampling settings */ | ||||
| #define BME680_OS_NONE		UINT8_C(0) | ||||
| #define BME680_OS_1X		UINT8_C(1) | ||||
| #define BME680_OS_2X		UINT8_C(2) | ||||
| #define BME680_OS_4X		UINT8_C(3) | ||||
| #define BME680_OS_8X		UINT8_C(4) | ||||
| #define BME680_OS_16X		UINT8_C(5) | ||||
| 
 | ||||
| /** IIR filter settings */ | ||||
| #define BME680_FILTER_SIZE_0	UINT8_C(0) | ||||
| #define BME680_FILTER_SIZE_1	UINT8_C(1) | ||||
| #define BME680_FILTER_SIZE_3	UINT8_C(2) | ||||
| #define BME680_FILTER_SIZE_7	UINT8_C(3) | ||||
| #define BME680_FILTER_SIZE_15	UINT8_C(4) | ||||
| #define BME680_FILTER_SIZE_31	UINT8_C(5) | ||||
| #define BME680_FILTER_SIZE_63	UINT8_C(6) | ||||
| #define BME680_FILTER_SIZE_127	UINT8_C(7) | ||||
| 
 | ||||
| /** Power mode settings */ | ||||
| #define BME680_SLEEP_MODE	UINT8_C(0) | ||||
| #define BME680_FORCED_MODE	UINT8_C(1) | ||||
| 
 | ||||
| /** Delay related macro declaration */ | ||||
| #define BME680_RESET_PERIOD		UINT32_C(10) | ||||
| 
 | ||||
| /** SPI memory page settings */ | ||||
| #define BME680_MEM_PAGE0	UINT8_C(0x10) | ||||
| #define BME680_MEM_PAGE1	UINT8_C(0x00) | ||||
| 
 | ||||
| /** Ambient humidity shift value for compensation */ | ||||
| #define BME680_HUM_REG_SHIFT_VAL	UINT8_C(4) | ||||
| 
 | ||||
| /** Run gas enable and disable settings */ | ||||
| #define BME680_RUN_GAS_DISABLE	UINT8_C(0) | ||||
| #define BME680_RUN_GAS_ENABLE	UINT8_C(1) | ||||
| 
 | ||||
| /** Buffer length macro declaration */ | ||||
| #define BME680_TMP_BUFFER_LENGTH	UINT8_C(40) | ||||
| #define BME680_REG_BUFFER_LENGTH	UINT8_C(6) | ||||
| #define BME680_FIELD_DATA_LENGTH	UINT8_C(3) | ||||
| #define BME680_GAS_REG_BUF_LENGTH	UINT8_C(20) | ||||
| #define BME680_GAS_HEATER_PROF_LEN_MAX  UINT8_C(10) | ||||
| 
 | ||||
| /** Settings selector */ | ||||
| #define BME680_OST_SEL			UINT16_C(1) | ||||
| #define BME680_OSP_SEL			UINT16_C(2) | ||||
| #define BME680_OSH_SEL			UINT16_C(4) | ||||
| #define BME680_GAS_MEAS_SEL		UINT16_C(8) | ||||
| #define BME680_FILTER_SEL		UINT16_C(16) | ||||
| #define BME680_HCNTRL_SEL		UINT16_C(32) | ||||
| #define BME680_RUN_GAS_SEL		UINT16_C(64) | ||||
| #define BME680_NBCONV_SEL		UINT16_C(128) | ||||
| #define BME680_GAS_SENSOR_SEL		UINT16_C(BME680_GAS_MEAS_SEL | BME680_RUN_GAS_SEL | BME680_NBCONV_SEL) | ||||
| 
 | ||||
| /** Number of conversion settings*/ | ||||
| #define BME680_NBCONV_MIN		UINT8_C(0) | ||||
| #define BME680_NBCONV_MAX		UINT8_C(10) | ||||
| 
 | ||||
| /** Mask definitions */ | ||||
| #define BME680_GAS_MEAS_MSK	UINT8_C(0x30) | ||||
| #define BME680_NBCONV_MSK	UINT8_C(0X0F) | ||||
| #define BME680_FILTER_MSK	UINT8_C(0X1C) | ||||
| #define BME680_OST_MSK		UINT8_C(0XE0) | ||||
| #define BME680_OSP_MSK		UINT8_C(0X1C) | ||||
| #define BME680_OSH_MSK		UINT8_C(0X07) | ||||
| #define BME680_HCTRL_MSK	UINT8_C(0x08) | ||||
| #define BME680_RUN_GAS_MSK	UINT8_C(0x10) | ||||
| #define BME680_MODE_MSK		UINT8_C(0x03) | ||||
| #define BME680_RHRANGE_MSK	UINT8_C(0x30) | ||||
| #define BME680_RSERROR_MSK	UINT8_C(0xf0) | ||||
| #define BME680_NEW_DATA_MSK	UINT8_C(0x80) | ||||
| #define BME680_GAS_INDEX_MSK	UINT8_C(0x0f) | ||||
| #define BME680_GAS_RANGE_MSK	UINT8_C(0x0f) | ||||
| #define BME680_GASM_VALID_MSK	UINT8_C(0x20) | ||||
| #define BME680_HEAT_STAB_MSK	UINT8_C(0x10) | ||||
| #define BME680_MEM_PAGE_MSK	UINT8_C(0x10) | ||||
| #define BME680_SPI_RD_MSK	UINT8_C(0x80) | ||||
| #define BME680_SPI_WR_MSK	UINT8_C(0x7f) | ||||
| #define	BME680_BIT_H1_DATA_MSK	UINT8_C(0x0F) | ||||
| 
 | ||||
| /** Bit position definitions for sensor settings */ | ||||
| #define BME680_GAS_MEAS_POS	UINT8_C(4) | ||||
| #define BME680_FILTER_POS	UINT8_C(2) | ||||
| #define BME680_OST_POS		UINT8_C(5) | ||||
| #define BME680_OSP_POS		UINT8_C(2) | ||||
| #define BME680_RUN_GAS_POS	UINT8_C(4) | ||||
| 
 | ||||
| /** Array Index to Field data mapping for Calibration Data*/ | ||||
| #define BME680_T2_LSB_REG	(1) | ||||
| #define BME680_T2_MSB_REG	(2) | ||||
| #define BME680_T3_REG		(3) | ||||
| #define BME680_P1_LSB_REG	(5) | ||||
| #define BME680_P1_MSB_REG	(6) | ||||
| #define BME680_P2_LSB_REG	(7) | ||||
| #define BME680_P2_MSB_REG	(8) | ||||
| #define BME680_P3_REG		(9) | ||||
| #define BME680_P4_LSB_REG	(11) | ||||
| #define BME680_P4_MSB_REG	(12) | ||||
| #define BME680_P5_LSB_REG	(13) | ||||
| #define BME680_P5_MSB_REG	(14) | ||||
| #define BME680_P7_REG		(15) | ||||
| #define BME680_P6_REG		(16) | ||||
| #define BME680_P8_LSB_REG	(19) | ||||
| #define BME680_P8_MSB_REG	(20) | ||||
| #define BME680_P9_LSB_REG	(21) | ||||
| #define BME680_P9_MSB_REG	(22) | ||||
| #define BME680_P10_REG		(23) | ||||
| #define BME680_H2_MSB_REG	(25) | ||||
| #define BME680_H2_LSB_REG	(26) | ||||
| #define BME680_H1_LSB_REG	(26) | ||||
| #define BME680_H1_MSB_REG	(27) | ||||
| #define BME680_H3_REG		(28) | ||||
| #define BME680_H4_REG		(29) | ||||
| #define BME680_H5_REG		(30) | ||||
| #define BME680_H6_REG		(31) | ||||
| #define BME680_H7_REG		(32) | ||||
| #define BME680_T1_LSB_REG	(33) | ||||
| #define BME680_T1_MSB_REG	(34) | ||||
| #define BME680_GH2_LSB_REG	(35) | ||||
| #define BME680_GH2_MSB_REG	(36) | ||||
| #define BME680_GH1_REG		(37) | ||||
| #define BME680_GH3_REG		(38) | ||||
| 
 | ||||
| /** BME680 register buffer index settings*/ | ||||
| #define BME680_REG_FILTER_INDEX		UINT8_C(5) | ||||
| #define BME680_REG_TEMP_INDEX		UINT8_C(4) | ||||
| #define BME680_REG_PRES_INDEX		UINT8_C(4) | ||||
| #define BME680_REG_HUM_INDEX		UINT8_C(2) | ||||
| #define BME680_REG_NBCONV_INDEX		UINT8_C(1) | ||||
| #define BME680_REG_RUN_GAS_INDEX	UINT8_C(1) | ||||
| #define BME680_REG_HCTRL_INDEX		UINT8_C(0) | ||||
| 
 | ||||
| /** Macro to combine two 8 bit data's to form a 16 bit data */ | ||||
| #define BME680_CONCAT_BYTES(msb, lsb)	(((uint16_t)msb << 8) | (uint16_t)lsb) | ||||
| 
 | ||||
| /** Macro to SET and GET BITS of a register */ | ||||
| #define BME680_SET_BITS(reg_data, bitname, data) \ | ||||
| 		((reg_data & ~(bitname##_MSK)) | \ | ||||
| 		((data << bitname##_POS) & bitname##_MSK)) | ||||
| #define BME680_GET_BITS(reg_data, bitname)	((reg_data & (bitname##_MSK)) >> \ | ||||
| 	(bitname##_POS)) | ||||
| 
 | ||||
| /** Macro variant to handle the bitname position if it is zero */ | ||||
| #define BME680_SET_BITS_POS_0(reg_data, bitname, data) \ | ||||
| 				((reg_data & ~(bitname##_MSK)) | \ | ||||
| 				(data & bitname##_MSK)) | ||||
| #define BME680_GET_BITS_POS_0(reg_data, bitname)  (reg_data & (bitname##_MSK)) | ||||
| 
 | ||||
| /** Type definitions */ | ||||
| /*
 | ||||
|  * Generic communication function pointer | ||||
|  * @param[in] dev_id: Place holder to store the id of the device structure | ||||
|  * 						Can be used to store the index of the Chip select or | ||||
|  * 						I2C address of the device. | ||||
|  * @param[in] reg_addr:	Used to select the register the where data needs to | ||||
|  * 						be read from or written to. | ||||
|  * @param[in/out] reg_data: Data array to read/write | ||||
|  * @param[in] len: Length of the data array | ||||
|  */ | ||||
| typedef int8_t (*bme680_com_fptr_t)(uint8_t dev_id, uint8_t reg_addr, uint8_t *data, uint16_t len); | ||||
| 
 | ||||
| /*
 | ||||
|  * Delay function pointer | ||||
|  * @param[in] period: Time period in milliseconds | ||||
|  */ | ||||
| typedef void (*bme680_delay_fptr_t)(uint32_t period); | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief Interface selection Enumerations | ||||
|  */ | ||||
| enum bme680_intf { | ||||
| 	/*! SPI interface */ | ||||
| 	BME680_SPI_INTF, | ||||
| 	/*! I2C interface */ | ||||
| 	BME680_I2C_INTF | ||||
| }; | ||||
| 
 | ||||
| /* structure definitions */ | ||||
| /*!
 | ||||
|  * @brief Sensor field data structure | ||||
|  */ | ||||
| struct	bme680_field_data { | ||||
| 	/*! Contains new_data, gasm_valid & heat_stab */ | ||||
| 	uint8_t status; | ||||
| 	/*! The index of the heater profile used */ | ||||
| 	uint8_t gas_index; | ||||
| 	/*! Measurement index to track order */ | ||||
| 	uint8_t meas_index; | ||||
| 	/*! Temperature in degree celsius x100 */ | ||||
| 	int16_t temperature; | ||||
| 	/*! Pressure in Pascal */ | ||||
| 	uint32_t pressure; | ||||
| 	/*! Humidity in % relative humidity x1000 */ | ||||
| 	uint32_t humidity; | ||||
| 	/*! Gas resistance in Ohms */ | ||||
| 	uint32_t gas_resistance; | ||||
| }; | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief Structure to hold the Calibration data | ||||
|  */ | ||||
| struct	bme680_calib_data { | ||||
| 	/*! Variable to store calibrated humidity data */ | ||||
| 	uint16_t par_h1; | ||||
| 	/*! Variable to store calibrated humidity data */ | ||||
| 	uint16_t par_h2; | ||||
| 	/*! Variable to store calibrated humidity data */ | ||||
| 	int8_t par_h3; | ||||
| 	/*! Variable to store calibrated humidity data */ | ||||
| 	int8_t par_h4; | ||||
| 	/*! Variable to store calibrated humidity data */ | ||||
| 	int8_t par_h5; | ||||
| 	/*! Variable to store calibrated humidity data */ | ||||
| 	uint8_t par_h6; | ||||
| 	/*! Variable to store calibrated humidity data */ | ||||
| 	int8_t par_h7; | ||||
| 	/*! Variable to store calibrated gas data */ | ||||
| 	int8_t par_gh1; | ||||
| 	/*! Variable to store calibrated gas data */ | ||||
| 	int16_t par_gh2; | ||||
| 	/*! Variable to store calibrated gas data */ | ||||
| 	int8_t par_gh3; | ||||
| 	/*! Variable to store calibrated temperature data */ | ||||
| 	uint16_t par_t1; | ||||
| 	/*! Variable to store calibrated temperature data */ | ||||
| 	int16_t par_t2; | ||||
| 	/*! Variable to store calibrated temperature data */ | ||||
| 	int8_t par_t3; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	uint16_t par_p1; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int16_t par_p2; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int8_t par_p3; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int16_t par_p4; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int16_t par_p5; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int8_t par_p6; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int8_t par_p7; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int16_t par_p8; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	int16_t par_p9; | ||||
| 	/*! Variable to store calibrated pressure data */ | ||||
| 	uint8_t par_p10; | ||||
| 	/*! Variable to store t_fine size */ | ||||
| 	int32_t t_fine; | ||||
| 	/*! Variable to store heater resistance range */ | ||||
| 	uint8_t res_heat_range; | ||||
| 	/*! Variable to store heater resistance value */ | ||||
| 	int8_t res_heat_val; | ||||
| 	/*! Variable to store error range */ | ||||
| 	int8_t range_sw_err; | ||||
| }; | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief BME680 sensor settings structure which comprises of ODR, | ||||
|  * over-sampling and filter settings. | ||||
|  */ | ||||
| struct	bme680_tph_sett { | ||||
| 	/*! Humidity oversampling */ | ||||
| 	uint8_t os_hum; | ||||
| 	/*! Temperature oversampling */ | ||||
| 	uint8_t os_temp; | ||||
| 	/*! Pressure oversampling */ | ||||
| 	uint8_t os_pres; | ||||
| 	/*! Filter coefficient */ | ||||
| 	uint8_t filter; | ||||
| }; | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief BME680 gas sensor which comprises of gas settings | ||||
|  *  and status parameters | ||||
|  */ | ||||
| struct	bme680_gas_sett { | ||||
| 	/*! Variable to store nb conversion */ | ||||
| 	uint8_t nb_conv; | ||||
| 	/*! Variable to store heater control */ | ||||
| 	uint8_t heatr_ctrl; | ||||
| 	/*! Run gas enable value */ | ||||
| 	uint8_t run_gas; | ||||
| 	/*! Pointer to store heater temperature */ | ||||
| 	uint16_t heatr_temp; | ||||
| 	/*! Pointer to store duration profile */ | ||||
| 	uint16_t heatr_dur; | ||||
| }; | ||||
| 
 | ||||
| /*!
 | ||||
|  * @brief BME680 device structure | ||||
|  */ | ||||
| struct	bme680_dev { | ||||
| 	/*! Chip Id */ | ||||
| 	uint8_t chip_id; | ||||
| 	/*! Device Id */ | ||||
| 	uint8_t dev_id; | ||||
| 	/*! SPI/I2C interface */ | ||||
| 	enum bme680_intf intf; | ||||
| 	/*! Memory page used */ | ||||
| 	uint8_t mem_page; | ||||
| 	/*! Ambient temperature in Degree C*/ | ||||
| 	int8_t amb_temp; | ||||
| 	/*! Sensor calibration data */ | ||||
| 	struct bme680_calib_data calib; | ||||
| 	/*! Sensor settings */ | ||||
| 	struct bme680_tph_sett tph_sett; | ||||
| 	/*! Gas Sensor settings */ | ||||
| 	struct bme680_gas_sett gas_sett; | ||||
| 	/*! Sensor power modes */ | ||||
| 	uint8_t power_mode; | ||||
| 	/*! New sensor fields */ | ||||
| 	uint8_t new_fields; | ||||
| 	/*! Store the info messages */ | ||||
| 	uint8_t info_msg; | ||||
| 	/*! Burst read structure */ | ||||
| 	bme680_com_fptr_t read; | ||||
| 	/*! Burst write structure */ | ||||
| 	bme680_com_fptr_t write; | ||||
| 	/*! Delay in ms */ | ||||
| 	bme680_delay_fptr_t delay_ms; | ||||
| 	/*! Communication function result */ | ||||
| 	int8_t com_rslt; | ||||
| }; | ||||
| 
 | ||||
| #endif /* BME680_DEFS_H_ */ | ||||
| /** @}*/ | ||||
| /** @}*/ | ||||
							
								
								
									
										733
									
								
								extras/bme680/bme680_drv.c
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										733
									
								
								extras/bme680/bme680_drv.c
									
										
									
									
									
										Normal file
									
								
							|  | @ -0,0 +1,733 @@ | |||
| /*
 | ||||
|  * Driver for Bosch Sensortec BME680 digital temperature, humity, pressure and | ||||
|  * gas sensor connected to I2C or SPI | ||||
|  * | ||||
|  * Part of esp-open-rtos [https://github.com/SuperHouse/esp-open-rtos]
 | ||||
|  * | ||||
|  * PLEASE NOTE:  | ||||
|  * Due to the complexity of the sensor output value computation based on many | ||||
|  * calibration parameters, the original Bosch Sensortec BME680 driver that is | ||||
|  * released as open source [https://github.com/BoschSensortec/BME680_driver]
 | ||||
|  * and integrated for internal use. Please note the license of this part, which | ||||
|  * is an extended BSD license and can be found in each of that source files. | ||||
|  * | ||||
|  * --------------------------------------------------------------------------- | ||||
|  * | ||||
|  * The BSD License (3-clause license) | ||||
|  * | ||||
|  * Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht]
 | ||||
|  * All rights reserved. | ||||
|  * | ||||
|  * Redistribution and use in source and binary forms, with or without | ||||
|  * modification, are permitted provided that the following conditions are met: | ||||
|  *  | ||||
|  * 1. Redistributions of source code must retain the above copyright notice, | ||||
|  * this list of conditions and the following disclaimer. | ||||
|  * | ||||
|  * 2. Redistributions in binary form must reproduce the above copyright | ||||
|  * notice, this list of conditions and the following disclaimer in the | ||||
|  * documentation and/or other materials provided with the distribution. | ||||
|  * | ||||
|  * 3. Neither the name of the copyright holder nor the names of its  | ||||
|  * contributors may be used to endorse or promote products derived from this | ||||
|  * software without specific prior written permission. | ||||
|  * | ||||
|  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||||
|  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||||
|  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE | ||||
|  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE | ||||
|  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR  | ||||
|  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF | ||||
|  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS | ||||
|  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN | ||||
|  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||||
|  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||||
|  * POSSIBILITY OF SUCH DAMAGE. | ||||
|  */ | ||||
| 
 | ||||
| #include <string.h> | ||||
|   | ||||
| #include "bme680_drv.h" | ||||
| #include "FreeRTOS.h" | ||||
| #include "task.h" | ||||
| 
 | ||||
| #include "espressif/esp_common.h" | ||||
| #include "espressif/sdk_private.h" | ||||
| 
 | ||||
| #ifdef BME680_DEBUG | ||||
| #define debug(s, f, ...) printf("%s %s: " s "\n", "BME680", f, ## __VA_ARGS__) | ||||
| #else | ||||
| #define debug(s, f, ...) | ||||
| #endif | ||||
| 
 | ||||
| #define error(s, f, ...) printf("%s %s: " s "\n", "BME680", f, ## __VA_ARGS__) | ||||
| 
 | ||||
| #define BME680_BG_TASK_PRIORITY        9 | ||||
| 
 | ||||
| /** 
 | ||||
|  * Forward declation of internal functions used by embedded Bosch Sensortec BME680 driver. | ||||
|  */ | ||||
| static void bme680_user_delay_ms(uint32_t period); | ||||
| static int8_t bme680_user_spi_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len); | ||||
| static int8_t bme680_user_spi_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len); | ||||
| static int8_t bme680_user_i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len); | ||||
| static int8_t bme680_user_i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len); | ||||
| 
 | ||||
| /**
 | ||||
|  * Sensor data structures | ||||
|  */ | ||||
| bme680_sensor_t bme680_sensors[BME680_MAX_SENSORS]; | ||||
| 
 | ||||
| /** */ | ||||
| 
 | ||||
| static bool bme680_valid_sensor (uint32_t sensor, const char* function) | ||||
| { | ||||
|     if (sensor < 0 || sensor > BME680_MAX_SENSORS) | ||||
|     { | ||||
|         debug("Wrong sensor id %d.", function, sensor); | ||||
|         return false; | ||||
|     } | ||||
|      | ||||
|     if (!bme680_sensors[sensor].active) | ||||
|     { | ||||
|         debug("Sensor with id %d is not active.", function, sensor); | ||||
|         return false; | ||||
|     } | ||||
|      | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| static bool bme680_is_available (uint32_t id) | ||||
| { | ||||
|     struct bme680_dev *dev = &bme680_sensors[id].dev; | ||||
| 
 | ||||
|     if (!bme680_valid_sensor(id, __FUNCTION__) ||  | ||||
|         bme680_get_regs(BME680_CHIP_ID_ADDR, &dev->chip_id, 1, dev) != BME680_OK) | ||||
|     { | ||||
|         return false; | ||||
|     } | ||||
| 
 | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| static void bme680_compute_values (uint8_t id, struct bme680_field_data* data) | ||||
| { | ||||
|     if (!bme680_valid_sensor(id, __FUNCTION__) || !data) | ||||
|         return; | ||||
| 
 | ||||
|     bme680_value_set_t  act; | ||||
|     bme680_value_set_t  avg = bme680_sensors[id].average; | ||||
|     float w = bme680_sensors[id].average_weight; | ||||
| 
 | ||||
|     act.temperature = bme680_sensors[id].dev.tph_sett.os_temp   ? data->temperature / 100.0f : 0; | ||||
|     act.pressure    = bme680_sensors[id].dev.tph_sett.os_pres   ? data->pressure / 100.0f : 0; | ||||
|     act.humidity    = bme680_sensors[id].dev.tph_sett.os_hum    ? data->humidity / 1000.0f : 0; | ||||
|     act.gas         = bme680_sensors[id].dev.gas_sett.heatr_dur ? data->gas_resistance : 0; | ||||
|    | ||||
|     if (bme680_sensors[id].average_first_measurement ||  | ||||
|         !bme680_sensors[id].average_computation) | ||||
|     { | ||||
|         bme680_sensors[id].average_first_measurement = false; | ||||
| 
 | ||||
|         avg = act; | ||||
|     } | ||||
|     else | ||||
|     { | ||||
|         avg.temperature = w * act.temperature + (1-w) * avg.temperature; | ||||
|         avg.humidity    = w * act.humidity    + (1-w) * avg.humidity; | ||||
|         avg.pressure    = w * act.pressure    + (1-w) * avg.pressure; | ||||
|         avg.gas         = w * act.gas         + (1-w) * avg.gas; | ||||
|     } | ||||
|     | ||||
|     bme680_sensors[id].actual  = act; | ||||
|     bme680_sensors[id].average = avg; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| static void bme680_background_task (void *pvParameters) | ||||
| { | ||||
|     uint32_t id = (uint32_t)pvParameters; | ||||
|     uint32_t next_time = sdk_system_get_time (); | ||||
|      | ||||
|     while (1)  | ||||
|     { | ||||
|         debug("%.3f Sensor %d", __FUNCTION__, (double)sdk_system_get_time()*1e-3, id); | ||||
| 
 | ||||
|         struct bme680_dev* dev = &bme680_sensors[id].dev; | ||||
|         struct bme680_field_data data; | ||||
|          | ||||
|         uint8_t set_required_settings; | ||||
|         int8_t rslt = BME680_OK; | ||||
| 
 | ||||
|     	/* Select the power mode */ | ||||
|     	/* Must be set before writing the sensor configuration */ | ||||
|     	dev->power_mode = BME680_FORCED_MODE;  | ||||
| 
 | ||||
|      	debug ("Using oversampling rates: %d %d %d", __FUNCTION__,  | ||||
|      	       bme680_sensors[id].dev.tph_sett.os_temp,  | ||||
|  	           bme680_sensors[id].dev.tph_sett.os_pres,  | ||||
|  	           bme680_sensors[id].dev.tph_sett.os_hum); | ||||
| 
 | ||||
|     	/* Set the required sensor settings needed */ | ||||
|     	set_required_settings = BME680_OST_SEL |  | ||||
|     	                        BME680_OSP_SEL |  | ||||
|     	                        BME680_OSH_SEL | | ||||
|     	                        BME680_FILTER_SEL |  | ||||
|     	                        BME680_GAS_SENSOR_SEL; | ||||
| 
 | ||||
|     	/* Set the desired sensor configuration */ | ||||
|     	rslt = bme680_set_sensor_settings(set_required_settings, dev); | ||||
| 
 | ||||
| 	    /* Set the power mode to forced mode to trigger one TPHG measurement cycle */ | ||||
|     	rslt = bme680_set_sensor_mode(dev); | ||||
| 
 | ||||
| 	    /* Get the total measurement duration so as to sleep or wait till the
 | ||||
|     	 * measurement is complete */ | ||||
|     	uint16_t meas_period; | ||||
|     	bme680_get_profile_dur(&meas_period, dev); | ||||
|     	vTaskDelay(meas_period/portTICK_PERIOD_MS); /* Delay till the measurement is ready */ | ||||
| 
 | ||||
|         if ((rslt = bme680_get_sensor_data(&data, dev)) == BME680_OK) | ||||
|         { | ||||
|            bme680_compute_values(id, &data); | ||||
|                  | ||||
|            debug("%d ms: %.2f C, %.2f Percent, %.2f hPa, %.2f Ohm", __FUNCTION__,  | ||||
|                  sdk_system_get_time (), | ||||
|                  bme680_sensors[id].actual.temperature, | ||||
|                  bme680_sensors[id].actual.humidity, | ||||
|                  bme680_sensors[id].actual.pressure, | ||||
|                  bme680_sensors[id].actual.gas); | ||||
| 
 | ||||
|             if (bme680_sensors[id].cb_function) | ||||
|                 bme680_sensors[id].cb_function(id, | ||||
|                                                bme680_sensors[id].actual, | ||||
|                                                bme680_sensors[id].average); | ||||
|                      | ||||
|         } | ||||
|         else | ||||
| 		    error("Could not get data from sensor with id %d", __FUNCTION__,id); | ||||
| 
 | ||||
| 		/* Compute next measurement time as well as remaining cycle time*/ | ||||
| 		uint32_t system_time = sdk_system_get_time (); | ||||
| 		uint32_t remaining_time; | ||||
| 
 | ||||
| 		next_time = next_time + bme680_sensors[id].period*1000; // in us
 | ||||
| 
 | ||||
|         if (next_time < system_time) | ||||
|             // in case of timer overflow
 | ||||
|             remaining_time = UINT32_MAX - system_time + next_time; | ||||
|         else | ||||
|             // normal case
 | ||||
|             remaining_time = next_time - system_time; | ||||
| 
 | ||||
|         /* Delay the background task by the cycle time */ | ||||
|         vTaskDelay(remaining_time/1000/portTICK_PERIOD_MS); | ||||
|     } | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_init_driver() | ||||
| { | ||||
|     for (int id=0; id < BME680_MAX_SENSORS; id++) | ||||
|         bme680_sensors[id].active = false; | ||||
|          | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| uint32_t bme680_create_sensor(uint8_t bus, uint8_t addr, uint8_t cs) | ||||
| { | ||||
|     static uint32_t id; | ||||
|     static char bg_task_name[20]; | ||||
|      | ||||
|     // search for first free sensor data structure
 | ||||
|     for (id=0; id < BME680_MAX_SENSORS; id++) | ||||
|     { | ||||
|         debug("id=%d active=%d", __FUNCTION__, id, bme680_sensors[id].active); | ||||
|         if (!bme680_sensors[id].active) | ||||
|             break; | ||||
|     } | ||||
|     debug("id=%d", __FUNCTION__, id); | ||||
|      | ||||
|     if (id == BME680_MAX_SENSORS) | ||||
|     { | ||||
|         debug("No more sensor data structures available.", __FUNCTION__); | ||||
|         return -1; | ||||
|     } | ||||
|     // init sensor data structure
 | ||||
|     bme680_sensors[id].bus  = bus; | ||||
|     bme680_sensors[id].addr = addr; | ||||
|     bme680_sensors[id].period = 1000; | ||||
|     bme680_sensors[id].average_computation = true; | ||||
|     bme680_sensors[id].average_first_measurement = true; | ||||
|     bme680_sensors[id].average_weight = 0.2; | ||||
|     bme680_sensors[id].cb_function = NULL; | ||||
|     bme680_sensors[id].bg_task = NULL; | ||||
| 
 | ||||
|     bme680_sensors[id].dev.dev_id = id; | ||||
| 
 | ||||
|     if (bme680_sensors[id].addr) | ||||
|     { | ||||
|         // I2C interface used
 | ||||
|         bme680_sensors[id].addr = addr; | ||||
|         bme680_sensors[id].dev.intf = BME680_I2C_INTF; | ||||
|         bme680_sensors[id].dev.read = bme680_user_i2c_read; | ||||
|         bme680_sensors[id].dev.write = bme680_user_i2c_write; | ||||
|         bme680_sensors[id].dev.delay_ms = bme680_user_delay_ms; | ||||
|     } | ||||
|     else | ||||
|     { | ||||
|         // SPI interface used
 | ||||
|         bme680_sensors[id].spi_cs_pin = cs; | ||||
|         bme680_sensors[id].dev.intf = BME680_SPI_INTF; | ||||
|         bme680_sensors[id].dev.read = bme680_user_spi_read; | ||||
|         bme680_sensors[id].dev.write = bme680_user_spi_write; | ||||
|         bme680_sensors[id].dev.delay_ms = bme680_user_delay_ms; | ||||
|          | ||||
|         gpio_enable(bme680_sensors[id].spi_cs_pin, GPIO_OUTPUT); | ||||
|         gpio_write (bme680_sensors[id].spi_cs_pin, true); | ||||
|     } | ||||
|      | ||||
|     // initialize embedded Bosch Sensortec driver
 | ||||
|     if (bme680_init(&bme680_sensors[id].dev)) | ||||
|     { | ||||
|         error("Could not initialize the sensor device with id %d", __FUNCTION__, id); | ||||
|         return -1; | ||||
|     } | ||||
|              | ||||
|     bme680_sensors[id].active = true; | ||||
|      | ||||
|  	/* Set the default temperature, pressure and humidity settings */ | ||||
|     bme680_set_oversampling_rates (id, os_1x, os_1x, os_1x); | ||||
|     bme680_set_filter_size (id, iir_size_3); | ||||
| 
 | ||||
| 	/* Set heater default profile 320 degree Celcius for 150 ms */ | ||||
|     bme680_set_heater_profile (id, 320, 150); | ||||
| 
 | ||||
|     // check whether sensor is available
 | ||||
|     if (!bme680_is_available(id)) | ||||
|     { | ||||
|         debug("Sensor with id %d is not available", __FUNCTION__, id); | ||||
|         bme680_sensors[id].active = false;     | ||||
|         return -1; | ||||
|     } | ||||
| 
 | ||||
|     snprintf (bg_task_name, 20, "bme680_bg_task_%d", id); | ||||
| 
 | ||||
|     if (xTaskCreate (bme680_background_task, bg_task_name, 256, (void*)id,  | ||||
|                      BME680_BG_TASK_PRIORITY,  | ||||
|                      &bme680_sensors[id].bg_task) != pdPASS) | ||||
|     { | ||||
|         vTaskDelete(bme680_sensors[id].bg_task); | ||||
|         error("Could not create the background task %s for sensor with id %d\n", | ||||
|                __FUNCTION__, bg_task_name, id); | ||||
|         bme680_sensors[id].active = false;     | ||||
|         return false; | ||||
|     } | ||||
| 
 | ||||
|     return id; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_delete_sensor(uint32_t sensor) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|     bme680_sensors[sensor].active = false; | ||||
|      | ||||
|     if (bme680_sensors[sensor].bg_task) | ||||
|         vTaskDelete(bme680_sensors[sensor].bg_task); | ||||
|      | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_set_measurement_period (uint32_t sensor, uint32_t period) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|     if (period < 20) | ||||
|         error("Period of %d ms is less than the minimum " | ||||
|               "period of 20 ms for sensor with id %d.",  | ||||
|               __FUNCTION__, period, sensor); | ||||
| 
 | ||||
|     bme680_sensors[sensor].period = period; | ||||
|      | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_set_callback_function (uint32_t sensor, bme680_cb_function_t bme680_user_function) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
|      | ||||
|     bme680_sensors[sensor].cb_function = bme680_user_function; | ||||
|      | ||||
|     debug("Set callback function done.", __FUNCTION__); | ||||
| 
 | ||||
|     return false; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_get_values(uint32_t sensor, bme680_value_set_t *actual, bme680_value_set_t *average) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|     if (actual)  *actual  = bme680_sensors[sensor].actual; | ||||
|     if (average) *average = bme680_sensors[sensor].average; | ||||
| 
 | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_enable_average_computation (uint32_t sensor, bool enabled) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|     bme680_sensors[sensor].average_computation = enabled; | ||||
|     bme680_sensors[sensor].average_first_measurement = enabled; | ||||
| 
 | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_set_average_weight (uint32_t sensor, float weight) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|     bme680_sensors[sensor].average_first_measurement = true; | ||||
|     bme680_sensors[sensor].average_weight = weight; | ||||
| 
 | ||||
|     return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_set_oversampling_rates (uint32_t sensor,  | ||||
|                                     bme680_oversampling_t ost, | ||||
|                                     bme680_oversampling_t osp, | ||||
|                                     bme680_oversampling_t osh) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|  	/* Set the temperature, pressure and humidity settings */ | ||||
|     bme680_sensors[sensor].dev.tph_sett.os_temp = ost; | ||||
|   	bme680_sensors[sensor].dev.tph_sett.os_pres = osp; | ||||
|  	bme680_sensors[sensor].dev.tph_sett.os_hum  = osh; | ||||
| 
 | ||||
|  	debug ("Setting oversampling rates done: osrt=%d osp=%d osrh=%d", __FUNCTION__,  | ||||
|  	       bme680_sensors[sensor].dev.tph_sett.os_temp,  | ||||
|  	       bme680_sensors[sensor].dev.tph_sett.os_pres,  | ||||
|  	       bme680_sensors[sensor].dev.tph_sett.os_hum); | ||||
|  	        | ||||
|  	bme680_sensors[sensor].average_first_measurement = true; | ||||
|                                         | ||||
|    	return true; | ||||
| } | ||||
| 
 | ||||
| bool bme680_set_heater_profile (uint32_t sensor, uint16_t temperature, uint16_t duration) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|  	/* Set the temperature, pressure and humidity settings */ | ||||
|     bme680_sensors[sensor].dev.gas_sett.heatr_temp = temperature; /* degree Celsius */ | ||||
|     bme680_sensors[sensor].dev.gas_sett.heatr_dur = duration; /* milliseconds */ | ||||
| 
 | ||||
|  	debug ("Setting heater profile done: temperature=%d duration=%d", __FUNCTION__,  | ||||
|  	       bme680_sensors[sensor].dev.gas_sett.heatr_temp,  | ||||
|  	       bme680_sensors[sensor].dev.gas_sett.heatr_dur); | ||||
|  	        | ||||
|     /* Set the remaining default gas sensor settings and link the heating profile */ | ||||
|     if (temperature == 0 || duration == 0) | ||||
|         bme680_sensors[sensor].dev.gas_sett.run_gas = BME680_DISABLE_GAS_MEAS; | ||||
|     else | ||||
|         bme680_sensors[sensor].dev.gas_sett.run_gas = BME680_ENABLE_GAS_MEAS; | ||||
| 
 | ||||
|  	bme680_sensors[sensor].average_first_measurement = true; | ||||
|                                         | ||||
|    	return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| bool bme680_set_filter_size(uint32_t sensor, bme680_filter_size_t size) | ||||
| { | ||||
|     if (!bme680_valid_sensor(sensor, __FUNCTION__)) | ||||
|         return false; | ||||
| 
 | ||||
|  	/* Set the temperature, pressure and humidity settings */ | ||||
| 	bme680_sensors[sensor].dev.tph_sett.filter = size; | ||||
| 
 | ||||
|  	debug ("Setting filter size done: size=%d", __FUNCTION__,  | ||||
|  	       bme680_sensors[sensor].dev.tph_sett.filter); | ||||
|  	        | ||||
|  	bme680_sensors[sensor].average_first_measurement = true; | ||||
|                                         | ||||
|    	return true; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| /** 
 | ||||
|  * Internal functions used by embedded Bosch Sensortec BME680 driver. | ||||
|  */ | ||||
| 
 | ||||
| static void bme680_user_delay_ms(uint32_t period) | ||||
| { | ||||
|     /*
 | ||||
|      * Return control or wait, | ||||
|      * for a period amount of milliseconds | ||||
|      */ | ||||
|       | ||||
|      vTaskDelay(period / portTICK_PERIOD_MS); | ||||
| } | ||||
| 
 | ||||
| #define BME680_SPI_BUF_SIZE 64      // SPI register data buffer size of ESP866
 | ||||
| 
 | ||||
| static const spi_settings_t bus_settings = { | ||||
|     .mode         = SPI_MODE0, | ||||
|     .freq_divider = SPI_FREQ_DIV_10M, | ||||
|     .msb          = true, | ||||
|     .minimal_pins = true, | ||||
|     .endianness   = SPI_LITTLE_ENDIAN | ||||
| }; | ||||
| 
 | ||||
| 
 | ||||
| static int8_t bme680_user_spi_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len) | ||||
| { | ||||
|     /*
 | ||||
|      * The parameter dev_id can be used as a variable to select which Chip Select pin has | ||||
|      * to be set low to activate the relevant device on the SPI bus | ||||
|      */ | ||||
| 
 | ||||
|     /*
 | ||||
|      * Data on the bus should be like | ||||
|      * |----------------+---------------------+-------------| | ||||
|      * | MOSI           | MISO                | Chip Select | | ||||
|      * |----------------+---------------------|-------------| | ||||
|      * | (don't care)   | (don't care)        | HIGH        | | ||||
|      * | (reg_addr)     | (don't care)        | LOW         | | ||||
|      * | (don't care)   | (reg_data[0])       | LOW         | | ||||
|      * | (....)         | (....)              | LOW         | | ||||
|      * | (don't care)   | (reg_data[len - 1]) | LOW         | | ||||
|      * | (don't care)   | (don't care)        | HIGH        | | ||||
|      * |----------------+---------------------|-------------| | ||||
|      */ | ||||
| 
 | ||||
|     // debug("dev_id=%d, reg_addr=%0x, len=%d\n", __FUNCTION__, dev_id, reg_addr, len);
 | ||||
| 
 | ||||
|     if (len >= BME680_SPI_BUF_SIZE) | ||||
|     { | ||||
|         error("Error on read from SPI slave on bus 1. Tried to transfer more" | ||||
|               "than %d byte in one read operation.", __FUNCTION__, BME680_SPI_BUF_SIZE); | ||||
|         return -1; | ||||
|     } | ||||
|      | ||||
|     spi_settings_t old_settings; | ||||
| 
 | ||||
|     static uint8_t mosi[BME680_SPI_BUF_SIZE]; | ||||
|     static uint8_t miso[BME680_SPI_BUF_SIZE]; | ||||
|      | ||||
|     memset (mosi, 0xff, BME680_SPI_BUF_SIZE); | ||||
|     memset (miso, 0xff, BME680_SPI_BUF_SIZE); | ||||
|      | ||||
|     mosi[0] = reg_addr; | ||||
|          | ||||
|     uint8_t bus = bme680_sensors[dev_id].bus; | ||||
|     uint8_t spi_cs_pin = bme680_sensors[dev_id].spi_cs_pin; | ||||
| 
 | ||||
|     spi_get_settings(bus, &old_settings); | ||||
|     spi_set_settings(bus, &bus_settings); | ||||
|     gpio_write(spi_cs_pin, false); | ||||
| 
 | ||||
|     size_t success = spi_transfer (bus, (const void*)mosi, (void*)miso, len+1, SPI_8BIT); | ||||
| 
 | ||||
|     gpio_write(spi_cs_pin, true); | ||||
|     spi_set_settings(bus, &old_settings); | ||||
| 
 | ||||
|     if (!success) | ||||
|     { | ||||
|         error("Could not read data from SPI bus %d", __FUNCTION__, bus); | ||||
|         return -1; | ||||
|     } | ||||
|      | ||||
|     for (int i=0; i < len; i++) | ||||
|       reg_data[i] = miso[i+1]; | ||||
|          | ||||
| #   ifdef BME680_DEBUG | ||||
|     printf("BME680 %s: Read the following bytes: ", __FUNCTION__); | ||||
|     printf("%0x ", reg_addr); | ||||
|     for (int i=0; i < len; i++) | ||||
|         printf("%0x ", reg_data[i]); | ||||
|     printf("\n"); | ||||
| #   endif         | ||||
|          | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| static int8_t bme680_user_spi_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len) | ||||
| { | ||||
|     /*
 | ||||
|      * The parameter dev_id can be used as a variable to select which Chip Select pin has | ||||
|      * to be set low to activate the relevant device on the SPI bus | ||||
|      */ | ||||
| 
 | ||||
|     /*
 | ||||
|      * Data on the bus should be like | ||||
|      * |---------------------+--------------+-------------| | ||||
|      * | MOSI                | MISO         | Chip Select | | ||||
|      * |---------------------+--------------|-------------| | ||||
|      * | (don't care)        | (don't care) | HIGH        | | ||||
|      * | (reg_addr)          | (don't care) | LOW         | | ||||
|      * | (reg_data[0])       | (don't care) | LOW         | | ||||
|      * | (....)              | (....)       | LOW         | | ||||
|      * | (reg_data[len - 1]) | (don't care) | LOW         | | ||||
|      * | (don't care)        | (don't care) | HIGH        | | ||||
|      * |---------------------+--------------|-------------| | ||||
|      */ | ||||
|       | ||||
|     static uint8_t mosi[BME680_SPI_BUF_SIZE]; | ||||
|      | ||||
|     if (len >= BME680_SPI_BUF_SIZE) | ||||
|     { | ||||
|         error("Error on write to SPI slave on bus 1. Tried to transfer more" | ||||
|               "than %d byte in one write operation.", __FUNCTION__, BME680_SPI_BUF_SIZE); | ||||
|         return -1;         | ||||
|     } | ||||
|      | ||||
|     mosi[0] = reg_addr; | ||||
|      | ||||
|     for (int i = 0; i < len; i++) | ||||
|         mosi[i+1] = reg_data[i]; | ||||
|          | ||||
| #   ifdef BME680_DEBUG | ||||
|     printf("BME680 %s: Write the following bytes: ", __FUNCTION__); | ||||
|     for (int i = 0; i < len+1; i++) | ||||
|         printf("%0x ", mosi[i]); | ||||
|     printf("\n"); | ||||
| #   endif | ||||
| 
 | ||||
|     spi_settings_t old_settings; | ||||
|      | ||||
|     uint8_t bus = bme680_sensors[dev_id].bus; | ||||
|     uint8_t spi_cs_pin = bme680_sensors[dev_id].spi_cs_pin; | ||||
| 
 | ||||
|     spi_get_settings(bus, &old_settings); | ||||
|     spi_set_settings(bus, &bus_settings); | ||||
|     gpio_write(spi_cs_pin, false); | ||||
| 
 | ||||
|     size_t success = spi_transfer (bus, (const void*)mosi, NULL, len+1, SPI_8BIT); | ||||
| 
 | ||||
|     gpio_write(spi_cs_pin, true); | ||||
|     spi_set_settings(bus, &old_settings); | ||||
| 
 | ||||
|     if (!success) | ||||
|     { | ||||
|         error("Could not write data to SPI bus %d", __FUNCTION__, bus); | ||||
|         return -1; | ||||
|     } | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| static int8_t bme680_user_i2c_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len) | ||||
| { | ||||
|     /*
 | ||||
|      * The parameter dev_id can be used as a variable to store the I2C address of the device | ||||
|      */ | ||||
| 
 | ||||
|     /*
 | ||||
|      * Data on the bus should be like | ||||
|      * |------------+---------------------| | ||||
|      * | I2C action | Data                | | ||||
|      * |------------+---------------------| | ||||
|      * | Start      | -                   | | ||||
|      * | Write      | (reg_addr)          | | ||||
|      * | Stop       | -                   | | ||||
|      * | Start      | -                   | | ||||
|      * | Read       | (reg_data[0])       | | ||||
|      * | Read       | (....)              | | ||||
|      * | Read       | (reg_data[len - 1]) | | ||||
|      * | Stop       | -                   | | ||||
|      * |------------+---------------------| | ||||
|      */ | ||||
| 
 | ||||
|     debug ("Read %d byte from i2c slave on bus %d with addr %0x.",  | ||||
|            __FUNCTION__, len, bme680_sensors[dev_id].bus, bme680_sensors[dev_id].addr); | ||||
| 
 | ||||
|     int result = i2c_slave_read(bme680_sensors[dev_id].bus,  | ||||
|                                 bme680_sensors[dev_id].addr,  | ||||
|                                 ®_addr, reg_data, len); | ||||
| 
 | ||||
|     if (result) | ||||
|     { | ||||
|         error("Error %d on read %d byte from I2C slave on bus %d with addr %0x.",  | ||||
|               __FUNCTION__, result, len, bme680_sensors[dev_id].bus, bme680_sensors[dev_id].addr); | ||||
|         return result; | ||||
|     } | ||||
| 
 | ||||
| #   ifdef BME680_DEBUG | ||||
|     printf("BME680 %s: Read following bytes: ", __FUNCTION__); | ||||
|     printf("%0x ", reg_addr); | ||||
|     for (int i=0; i < len; i++) | ||||
|         printf("%0x ", reg_data[i]); | ||||
|     printf("\n"); | ||||
| #   endif | ||||
| 
 | ||||
|     return result; | ||||
| } | ||||
| 
 | ||||
| static int8_t bme680_user_i2c_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint16_t len) | ||||
| { | ||||
|    /*
 | ||||
|      * The parameter dev_id can be used as a variable to store the I2C address of the device | ||||
|      */ | ||||
| 
 | ||||
|     /*
 | ||||
|      * Data on the bus should be like | ||||
|      * |------------+---------------------| | ||||
|      * | I2C action | Data                | | ||||
|      * |------------+---------------------| | ||||
|      * | Start      | -                   | | ||||
|      * | Write      | (reg_addr)          | | ||||
|      * | Write      | (reg_data[0])       | | ||||
|      * | Write      | (....)              | | ||||
|      * | Write      | (reg_data[len - 1]) | | ||||
|      * | Stop       | -                   | | ||||
|      * |------------+---------------------| | ||||
|      */ | ||||
| 
 | ||||
|     debug ("Write %d byte to i2c slave on bus %d with addr %0x.",  | ||||
|            __FUNCTION__, len, bme680_sensors[dev_id].bus, bme680_sensors[dev_id].addr); | ||||
| 
 | ||||
|     int result = i2c_slave_write(bme680_sensors[dev_id].bus,  | ||||
|                                  bme680_sensors[dev_id].addr,  | ||||
|                                  ®_addr, reg_data, len); | ||||
|    | ||||
|     if (result) | ||||
|     { | ||||
|         error("Error %d on write to i2c slave on bus %d with addr %0x.",  | ||||
|                __FUNCTION__, result, bme680_sensors[dev_id].bus, bme680_sensors[dev_id].addr); | ||||
|         return result; | ||||
|     } | ||||
| 
 | ||||
| #   ifdef BME680_DEBUG | ||||
|     printf("BME680 %s: Wrote the following bytes: ", __FUNCTION__); | ||||
|     printf("%0x ", reg_addr); | ||||
|     for (int i=0; i < len; i++) | ||||
|         printf("%0x ", reg_data[i]); | ||||
|     printf("\n"); | ||||
| #   endif | ||||
|        | ||||
|     return result; | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										398
									
								
								extras/bme680/bme680_drv.h
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										398
									
								
								extras/bme680/bme680_drv.h
									
										
									
									
									
										Normal file
									
								
							|  | @ -0,0 +1,398 @@ | |||
| /*
 | ||||
|  * Driver for Bosch Sensortec BME680 digital temperature, humity, pressure and | ||||
|  * gas sensor connected to I2C or SPI | ||||
|  * | ||||
|  * Part of esp-open-rtos [https://github.com/SuperHouse/esp-open-rtos]
 | ||||
|  * | ||||
|  * PLEASE NOTE:  | ||||
|  * Due to the complexity of the sensor output value compputation based on many | ||||
|  * calibration parameters, the original Bosch Sensortec BME680 driver that is | ||||
|  * released as open source [https://github.com/BoschSensortec/BME680_driver]
 | ||||
|  * and integrated for internal use. Please note the license of this part, which | ||||
|  * is an extended BSD license and can be found in each of that source files. | ||||
|  * | ||||
|  * --------------------------------------------------------------------------- | ||||
|  * | ||||
|  * The BSD License (3-clause license) | ||||
|  * | ||||
|  * Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht]
 | ||||
|  * All rights reserved. | ||||
|  * | ||||
|  * Redistribution and use in source and binary forms, with or without | ||||
|  * modification, are permitted provided that the following conditions are met: | ||||
|  *  | ||||
|  * 1. Redistributions of source code must retain the above copyright notice, | ||||
|  * this list of conditions and the following disclaimer. | ||||
|  * | ||||
|  * 2. Redistributions in binary form must reproduce the above copyright | ||||
|  * notice, this list of conditions and the following disclaimer in the | ||||
|  * documentation and/or other materials provided with the distribution. | ||||
|  * | ||||
|  * 3. Neither the name of the copyright holder nor the names of its  | ||||
|  * contributors may be used to endorse or promote products derived from this | ||||
|  * software without specific prior written permission. | ||||
|  * | ||||
|  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" | ||||
|  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE | ||||
|  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE | ||||
|  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE | ||||
|  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR  | ||||
|  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF | ||||
|  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS | ||||
|  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN | ||||
|  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) | ||||
|  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||||
|  * POSSIBILITY OF SUCH DAMAGE. | ||||
|  */ | ||||
| 
 | ||||
| #ifndef BME680_DRV_H_ | ||||
| #define BME680_DRV_H_ | ||||
| 
 | ||||
| #include "stdint.h" | ||||
| #include "stdbool.h" | ||||
| 
 | ||||
| #include "FreeRTOS.h" | ||||
| #include <task.h> | ||||
| 
 | ||||
| #include "i2c/i2c.h" | ||||
| #include "esp/spi.h" | ||||
| 
 | ||||
| #include "bme680/bme680.h" | ||||
| 
 | ||||
| // Uncomment to enable debug output
 | ||||
| // #define BME680_DEBUG
 | ||||
| 
 | ||||
| // Change this if you need more than 3 BME680 sensors
 | ||||
| #define BME680_MAX_SENSORS 3 | ||||
| 
 | ||||
| #ifdef __cplusplus | ||||
| extern "C" | ||||
| { | ||||
| #endif | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	Type for actual and average sensor values (called TPHG values) | ||||
|  */ | ||||
| typedef struct { | ||||
|     float   temperature;    // temperature in degree Celcius
 | ||||
|     float   pressure;       // barometric pressure in hPascal
 | ||||
|     float   humidity;       // humidity in percent
 | ||||
|     float   gas;            // gas resistance in Ohm
 | ||||
| } bme680_value_set_t; | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	callback unction type to pass result of measurement to user tasks | ||||
|  */ | ||||
| typedef void (*bme680_cb_function_t)(uint32_t sensor, | ||||
|                                     bme680_value_set_t actual,  | ||||
|                                     bme680_value_set_t average); | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief 	BME680 sensor device data structure type | ||||
|  */ | ||||
| typedef struct { | ||||
| 
 | ||||
|     bool     active; | ||||
|      | ||||
|     uint8_t  bus;               // I2C = 0, SPI = 1
 | ||||
|     uint8_t  addr;              // I2C = slave address, SPI = 0
 | ||||
|     uint8_t  spi_cs_pin;        // GPIO used as SPI CS
 | ||||
| 
 | ||||
|     uint32_t period; | ||||
| 
 | ||||
|     bme680_value_set_t  actual; | ||||
|     bme680_value_set_t  average; | ||||
|      | ||||
|     bool	average_computation; | ||||
|     bool    average_first_measurement; | ||||
|     float   average_weight; | ||||
| 
 | ||||
|     bme680_cb_function_t cb_function; | ||||
|     TaskHandle_t         bg_task; | ||||
|      | ||||
|     struct bme680_dev dev;  // internal Bosch BME680 driver data structure
 | ||||
|      | ||||
| } bme680_sensor_t; | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief 	BME680 oversampling rate values | ||||
|  */ | ||||
| typedef enum { | ||||
|     none   = 0,     // measurement is skipped, output values are invalid
 | ||||
|     os_1x  = 1,     // default oversampling rates
 | ||||
|     os_2x  = 2, | ||||
|     os_4x  = 3, | ||||
|     os_8x  = 4, | ||||
|     os_16x = 5 | ||||
| } bme680_oversampling_t; | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief 	BME680 IIR filter sizes | ||||
|  */ | ||||
| typedef enum { | ||||
|     iir_size_0   = 0,   // filter is not used
 | ||||
|     iir_size_1   = 1, | ||||
|     iir_size_3   = 2, | ||||
|     iir_size_7   = 3, | ||||
|     iir_size_15  = 4, | ||||
|     iir_size_31  = 5, | ||||
|     iir_size_63  = 6, | ||||
|     iir_size_127 = 7 | ||||
| } bme680_filter_size_t; | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	Initialize the BME680 driver | ||||
|  * | ||||
|  * This function initializes all internal data structures. It must be called | ||||
|  * exactly once at the beginning. | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_init_driver (); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	Create and initialize a BME680 sensor | ||||
|  *  | ||||
|  * This function initializes the BME680 sensor and checks its availability. | ||||
|  * | ||||
|  * Furthermore, the starts a background task for measurements with  | ||||
|  * the sensor. The background task carries out the measurements periodically | ||||
|  * using BME680's single shot data acquisition mode with a default period  | ||||
|  * of 1000 ms. This period be changed using function *set_measurment_period*. | ||||
|  *  | ||||
|  * During each measurement the background task  | ||||
|  * | ||||
|  *	1. determines *actual sensor values* | ||||
|  *  2. computes optionally *average sensor values* | ||||
|  *	3. calls back optionally a registered function of user task. | ||||
|  * | ||||
|  * The average value computation uses an exponential moving average  | ||||
|  * and can be activated (default) or deactivated with function  | ||||
|  * *bme680_enable_average_computation*. If the average value computation is | ||||
|  * deactivated, *average sensor values* correspond to *actual sensor values*. | ||||
|  * The weight (smoothing factor) used in the average value computatoin is 0.2  | ||||
|  * by default and can be changed with function *bme680_set_average_weight*. | ||||
|  * | ||||
|  * If a callback method has been registered with function  | ||||
|  * *bme680_set_callback_function*, it is called after each measurement | ||||
|  * to pass measurement results to user tasks. Otherwise, user tasks have to | ||||
|  * use function *bme680_get_values* explicitly to get the results. | ||||
|  * | ||||
|  * The sensor can either be connected to an I2C or SPI bus. If *addr* is | ||||
|  * greater than 0, it defines a valid I2C slave address and the sensor is | ||||
|  * connected to an I2C bus using this address. If *addr* is 0, the sensor | ||||
|  * is connected to a SPI bus. In both cases, the *bus* parameter specifies | ||||
|  * the ID of the corresponding bus. In case of SPI, parameter *cs* defines | ||||
|  * the GPIO used as CS signal. | ||||
|  * | ||||
|  * @param   bus     I2C or SPI bus at which BME680 sensor is connected | ||||
|  * @param   addr    I2C addr of the BME680 sensor or 0 for SPI | ||||
|  * @param   cs      SPI CS GPIO, ignored for I2C | ||||
|  * | ||||
|  * @return  ID of the sensor (0 or greater on success or -1 on error) | ||||
|  */ | ||||
| uint32_t bme680_create_sensor (uint8_t bus, uint8_t addr, uint8_t cs_pin); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief 	Set the period of the background measurement task for the given | ||||
|  *			sensor | ||||
|  * | ||||
|  * Please note: The minimum period is 20 ms since each measurement takes | ||||
|  * about 20 ms. | ||||
|  * | ||||
|  * @param   sensor  ID of the sensor | ||||
|  * @param   period  Measurement period in ms (default 1000 ms) | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_set_measurement_period (uint32_t sensor, uint32_t period); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief 	Set the callback function for the background measurement task for | ||||
|  *			the given sensor | ||||
|  * | ||||
|  * If a callback method is registered, it is called after each measurement to | ||||
|  * pass measurement results to user tasks. Thus, callback function is executed | ||||
|  * at the same rate as the measurements. | ||||
|  * | ||||
|  * @param   sensor      ID of the sensor | ||||
|  * @param   function    user function called after each measurement | ||||
|  *                      (NULL to delete it for the sensor) | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */  | ||||
| bool bme680_set_callback_function (uint32_t sensor,  | ||||
|                                   bme680_cb_function_t user_function); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	Deletes the BME680 sensor given by its ID | ||||
|  * | ||||
|  * @param   sensor   ID of the sensor | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_delete_sensor (uint32_t sensor); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	Get the actual and average sensor values | ||||
|  * | ||||
|  * This function returns the actual and average sensor values of the last | ||||
|  * measurement. The parameters *actual* and *average* are pointers to data | ||||
|  * structures of the type *bme680_value_set_t*, which are filled with the | ||||
|  * of last measurement. Use NULL for the appropriate parameter if you are | ||||
|  * not interested in specific results. | ||||
|  * | ||||
|  * If average value computation is deactivated, average sensor values  | ||||
|  * correspond to the actual sensor values. | ||||
|  * | ||||
|  * Please note: Calling this function is only necessary if no callback | ||||
|  * function has been registered for the sensor. | ||||
|  * | ||||
|  * @param   sensor    ID of the sensor | ||||
|  * @param   actual    Pointer to a data structure for actual sensor values | ||||
|  * @param   average   Pointer to a data structure for average sensor values | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_get_values (uint32_t sensor,  | ||||
|                        bme680_value_set_t *actual,  | ||||
|                        bme680_value_set_t *average); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	Enable (default) or disable the average value computation | ||||
|  *  | ||||
|  * In case, the average value computation is disabled, average sensor values | ||||
|  * correspond to the actual sensor values. | ||||
|  * | ||||
|  * Please note: All average sensor values are reset if parameters for | ||||
|  * measurement are changed using either function *bme680_set_average_weight*, | ||||
|  * *bme680_set_oversampling_rates*, *bme680_set_heater_profile* or | ||||
|  * *bme680_set_filter_size*. | ||||
|  * | ||||
|  * @param   sensor    id of the sensor | ||||
|  * @param	enabled	  true to enable or false to disable average computation | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
| */ | ||||
| bool bme680_enable_average_computation (uint32_t sensor, bool enabled); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief	Set the weight (smoothing factor) for average value computation | ||||
|  *  | ||||
|  * At each measurement carried out by the background task, actual sensor | ||||
|  * values are determined. If average value computation is enabled (default), | ||||
|  * exponential moving average values are computed according to following  | ||||
|  * equation | ||||
|  * | ||||
|  *    Average[k] = W * Value + (1-W) * Average [k-1] | ||||
|  * | ||||
|  * where coefficient W represents the degree of weighting decrease, a constant | ||||
|  * smoothing factor between 0 and 1. A higher W discounts older observations | ||||
|  * faster. W is 0.2 by default. | ||||
|  * | ||||
|  * @param   sensor  id of the sensor | ||||
|  * @param   weight  coefficient W (default is 0.2) | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_set_average_weight (uint32_t sensor, float weight); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief   Set the oversampling rates for measurements | ||||
|  *  | ||||
|  * The BME680 sensor allows to define different oversampling rates for the | ||||
|  * measurements of temperature, pressure and humidity, separatly. Possible | ||||
|  * oversampling rates defined by enumaration type are none, 1x (default),  | ||||
|  * 2x, 4x, 8x, and 16x. In case of *none*, the corressponing measurement is | ||||
|  * skipped and output values are invalid. | ||||
|  * | ||||
|  * Please note: To disable the measurement of either temperature, pressure | ||||
|  * or humidity, set the corresponding oversamling rate to *none*. | ||||
|  * | ||||
|  * @param   sensor  id of the sensor | ||||
|  * @param   ost     oversampling rate for temperature measurements | ||||
|  * @param   osp     oversampling rate for pressure measurements | ||||
|  * @param   osh     oversampling rate for humidity measurements | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_set_oversampling_rates (uint32_t sensor,  | ||||
|                                     bme680_oversampling_t ost, | ||||
|                                     bme680_oversampling_t osp, | ||||
|                                     bme680_oversampling_t osh); | ||||
|                                      | ||||
| /**
 | ||||
|  * @brief   Set the heater profile for gas measurements | ||||
|  * | ||||
|  * For gas measurement the sensor integrates a heater. The paremeters for | ||||
|  * this heater are defined by a heater profile. Such a heater profile | ||||
|  * consists of a temperature setting point (the target temperature) and the | ||||
|  * heating duration.  | ||||
|  * | ||||
|  * Even though the sensor supports up to 10 different profiles, only one  | ||||
|  * profile is used by this driver for simplicity. The temperature setting | ||||
|  * point and the heating duration of this profile can be defined by this | ||||
|  * function. Default values are 320 degree Celcius as target temperature and | ||||
|  * 150 ms heating duration. If heating duration is 0 ms, the gas measurement | ||||
|  * is skipped and output values are invalid. | ||||
|  * | ||||
|  * Please note: To disable the measurement of gas, set the heating duration | ||||
|  * to 0 ms. | ||||
|  * | ||||
|  * Please note: According to the datasheet, target temperatures of 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. | ||||
|  * | ||||
|  * @param   sensor        id of the sensor | ||||
|  * @param   temperature   heating temperature in degree Celcius | ||||
|  * @param   duration      heating duration in milliseconds | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_set_heater_profile (uint32_t sensor,  | ||||
|                                 uint16_t temperature,  | ||||
|                                 uint16_t duration); | ||||
| 
 | ||||
| 
 | ||||
| /**
 | ||||
|  * @brief   Set the size of the IIR filter | ||||
|  * | ||||
|  * The sensor 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. | ||||
|  * | ||||
|  * The filter can optionally be used for pressure and temperature data that | ||||
|  * are subject to many short-term changes. Humidity and gas inside the sensor | ||||
|  * does not fluctuate rapidly and does not require such a low pass filtering. | ||||
|  *  | ||||
|  * This function sets the size of the filter. The default filter size is | ||||
|  * 3 (iir_size_3). | ||||
|  *  | ||||
|  * Please note: If the size of the filter is 0, the filter is not used. | ||||
|  * | ||||
|  * @param   sensor  id of the sensor | ||||
|  * @param   size    IIR filter size | ||||
|  * | ||||
|  * @return  true on success, false on error | ||||
|  */ | ||||
| bool bme680_set_filter_size(uint32_t sensor, bme680_filter_size_t size); | ||||
| 
 | ||||
| 
 | ||||
| 
 | ||||
| #ifdef __cplusplus | ||||
| } | ||||
| #endif /* End of CPP guard */ | ||||
| 
 | ||||
| #endif /* BME680_DRV_H_ */ | ||||
| 
 | ||||
							
								
								
									
										9
									
								
								extras/bme680/component.mk
									
										
									
									
									
										Normal file
									
								
							
							
						
						
									
										9
									
								
								extras/bme680/component.mk
									
										
									
									
									
										Normal file
									
								
							|  | @ -0,0 +1,9 @@ | |||
| # Component makefile for extras/bme60
 | ||||
| 
 | ||||
| # expected anyone using bme680 driver includes it as 'bme680/bme680.h'
 | ||||
| INC_DIRS += $(bme680_ROOT)..  | ||||
| 
 | ||||
| # args for passing into compile rule generation
 | ||||
| bme680_SRC_DIR =  $(bme680_ROOT) | ||||
| 
 | ||||
| $(eval $(call component_compile_rules,bme680)) | ||||
		Loading…
	
	Add table
		Add a link
		
	
		Reference in a new issue