- minor changes

- changes to use the same source code with ESP8266 (esp-open-rtos) and
  ESP32 (ESP-IDF)
This commit is contained in:
Gunar Schorcht 2017-12-21 18:58:52 +01:00
parent c3ae04c93f
commit 07f3c08244
10 changed files with 398 additions and 254 deletions

View file

@ -11,8 +11,8 @@ For examples using BME680 sensor as I2C slave, just use GPIO5 (SCL) and GPIO4 (S
```
+-------------------------+ +--------+
| ESP8266 Bus 0 | | BME680 |
| GPIO 5 (SCL) +---->+ SCL |
| GPIO 4 (SDA) +-----+ SDA |
| GPIO 14 (SCL) ------> SCL |
| GPIO 13 (SDA) <-----> SDA |
| | +--------+
+-------------------------+
```
@ -22,10 +22,10 @@ For examples that are using SPI, BME680 sensor has to be connected to SPI bus 1.
```
+-------------------------+ +----------+
| ESP8266 Bus 1 | | BME680 |
| GPIO 12 (MISO) <-----< SDO |
| GPIO 13 (MOSI) >-----> SDI |
| GPIO 14 (SCK) >-----> SCK |
| GPIO 2 (CS) >-----> CS |
| GPIO 14 (SCK) ------> SCK |
| GPIO 13 (MOSI) ------> SDI |
| GPIO 12 (MISO) <------ SDO |
| GPIO 2 (CS) ------> CS |
+-------------------------+ +----------+
```

View file

@ -6,8 +6,8 @@
*
* I2C +-------------------------+ +----------+
* | ESP8266 Bus 0 | | BME680 |
* | GPIO 5 (SCL) ------> SCL |
* | GPIO 4 (SDA) ------- SDA |
* | GPIO 14 (SCL) ------> SCL |
* | GPIO 13 (SDA) ------- SDA |
* +-------------------------+ +----------+
*/
@ -25,8 +25,8 @@
// define I2C interface for BME680 sensors
#define I2C_BUS 0
#define I2C_SCL_PIN 5
#define I2C_SDA_PIN 4
#define I2C_SCL_PIN 14
#define I2C_SDA_PIN 13
static bme680_sensor_t* sensor;
@ -91,13 +91,13 @@ void user_init(void)
/** -- MANDATORY PART -- */
#ifdef SPI_USED
// Init the sensor connected either to SPI.
// Init the sensor connected to SPI.
sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO);
#else
// 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 the sensor connected either to I2C.
// Init the sensor connected to I2C.
sensor = bme680_init_sensor (I2C_BUS, BME680_I2C_ADDRESS_2, 0);
#endif

View file

@ -4,50 +4,72 @@
*
* Harware configuration:
*
* I2C +-------------------------+ +----------+
* | ESP8266 Bus 0 | | BME680 |
* | GPIO 5 (SCL) ------> SCL |
* | GPIO 4 (SDA) ------- SDA |
* +-------------------------+ +----------+
* I2C
*
* SPI +-------------------------+ +----------+
* | ESP8266 Bus 1 | | BME680 |
* | GPIO 12 (MISO) <-----< SDO |
* | GPIO 13 (MOSI) >-----> SDI |
* | GPIO 14 (SCK) >-----> SCK |
* | GPIO 2 (CS) >-----> CS |
* +-------------------------+ +----------+
* +-----------------+ +----------+
* | ESP8266 / ESP32 | | BME680 |
* | | | |
* | GPIO 14 (SCL) ----> SCL |
* | GPIO 13 (SDA) <---> SDA |
* +-----------------+ +----------+
*
* SPI
*
* +-----------------+ +----------+ +-----------------+ +----------+
* | ESP8266 | | BME680 | | ESP32 | | BME680 |
* | | | | | | | |
* | GPIO 14 (SCK) ----> SCK | | GPIO 16 (SCK) ----> SCK |
* | GPIO 13 (MOSI)----> SDI | | GPIO 17 (MOSI)----> SDI |
* | GPIO 12 (MISO)<---- SDO | | GPIO 18 (MISO)<---- SDO |
* | GPIO 2 (CS) ----> CS | | GPIO 19 (CS) ----> CS |
* +-----------------+ +---------+ +-----------------+ +----------+
*/
// Uncomment to use SPI
/* -- use following constants to define the example mode ----------- */
// #define SPI_USED
#include "espressif/esp_common.h"
#include "esp/uart.h"
/* -- includes ----------------------------------------------------- */
#include "FreeRTOS.h"
#include "task.h"
#include "bme680.h"
// include communication interface driver
#include "esp/spi.h"
#include "i2c/i2c.h"
/* -- platform dependent definitions ------------------------------- */
// include BME680 driver
#include "bme680/bme680.h"
#ifdef ESP_PLATFORM // ESP32 (ESP-IDF)
// user task stack depth for ESP32
#define TASK_STACK_DEPTH 2048
#ifdef SPI_USED
// define SPI interface for BME680 sensors
#define SPI_BUS 1
#define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used
#else
// define I2C interface for BME680 sensors
#define I2C_BUS 0
#define I2C_SCL_PIN 5
#define I2C_SDA_PIN 4
#endif
// SPI interface definitions for ESP32
#define SPI_BUS HSPI_HOST
#define SPI_SCK_GPIO 16
#define SPI_MOSI_GPIO 17
#define SPI_MISO_GPIO 18
#define SPI_CS_GPIO 19
static bme680_sensor_t* sensor;
#else // ESP8266 (esp-open-rtos)
// user task stack depth for ESP8266
#define TASK_STACK_DEPTH 256
// SPI interface definitions for ESP8266
#define SPI_BUS 1
#define SPI_SCK_GPIO 14
#define SPI_MOSI_GPIO 13
#define SPI_MISO_GPIO 12
#define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used
#endif // ESP_PLATFORM
// I2C interface defintions for ESP32 and ESP8266
#define I2C_BUS 0
#define I2C_SCL_PIN 14
#define I2C_SDA_PIN 13
#define I2C_FREQ I2C_FREQ_100K
/* -- user tasks --------------------------------------------------- */
static bme680_sensor_t* sensor = 0;
/*
* User task that triggers measurements of sensor every seconds. It uses
@ -86,31 +108,38 @@ void user_task(void *pvParameters)
}
}
/* -- main program ------------------------------------------------- */
void user_init(void)
{
// Set UART Parameter
// Set UART Parameter.
uart_set_baud(0, 115200);
// Give the UART some time to settle
sdk_os_delay_us(500);
vTaskDelay(1);
/** -- MANDATORY PART -- */
#ifdef SPI_USED
// Init the sensor connected either to SPI.
sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO);
#else
// 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 the sensor connected either to I2C.
spi_bus_init (SPI_BUS, SPI_SCK_GPIO, SPI_MISO_GPIO, SPI_MOSI_GPIO);
// init the sensor connected to SPI_BUS with SPI_CS_GPIO as chip select.
sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO);
#else // I2C
// Init all I2C bus interfaces at which BME680 sensors are connected
i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ);
// init the sensor with slave address BME680_I2C_ADDRESS_2 connected to I2C_BUS.
sensor = bme680_init_sensor (I2C_BUS, BME680_I2C_ADDRESS_2, 0);
#endif
#endif // SPI_USED
if (sensor)
{
// Create a task that uses the sensor
xTaskCreate(user_task, "user_task", 256, NULL, 2, NULL);
xTaskCreate(user_task, "user_task", TASK_STACK_DEPTH, NULL, 2, NULL);
/** -- OPTIONAL PART -- */

View file

@ -8,14 +8,14 @@
* Harware configuration:
*
* +-------------------------+ +----------+
* | ESP8266 I2C Bus 0 | | BME680_1 |
* | ESP8266 I2C Bus 1 | | BME680_1 |
* | GPIO 5 (SCL) ------> SCL |
* | GPIO 4 (SDA) ------- SDA |
* | GPIO 4 (SDA) <-----> SDA |
* | | +----------+
* | SPI Bus 1 | | BME680_2 |
* | GPIO 12 (MISO) <------ SDO |
* | GPIO 13 (MOSI) >-----> SDI |
* | GPIO 14 (SCK) >-----> SCK |
* | GPIO 13 (MOSI) >-----> SDI |
* | GPIO 12 (MISO) <------ SDO |
* | GPIO 2 (CS) >-----> CS |
* +-------------------------+ +----------+
*/
@ -37,7 +37,7 @@
#define SPI_BUS 1
#define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used
// define SPI interface for BME680 sensor 2
#define I2C_BUS 0
#define I2C_BUS 1
#define I2C_SCL_PIN 5
#define I2C_SDA_PIN 4
@ -122,7 +122,7 @@ void user_init(void)
// 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 the sensors connected to different I2C buses with same address
// Init the sensors
sensor1 = bme680_init_sensor (I2C_BUS, BME680_I2C_ADDRESS_2, 0);
sensor2 = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO);

View file

@ -1,6 +1,9 @@
# Driver for **BME680** digital **environmental sensor**
This driver is written for usage with the ESP8266 and FreeRTOS. It supports multiple BME680 sensors which are either connected to the SPI or to different I2C interfaces with different addresses.
The driver supports multiple BME680 sensors which are either connected to the SPI or to the same or different I2C interfaces with different addresses.
It is for the usage with the ESP8266 and [esp-open-rtos](https://github.com/SuperHouse/esp-open-rtos).
The driver is also working with ESP32 and [ESP-IDF](https://github.com/espressif/esp-idf.git) using a wrapper component for ESP8266 functions, see folder ```components/esp8266_wrapper```, as well as Linux based systems using a wrapper library.
## About the sensor
@ -234,8 +237,8 @@ else
switch (sensor->error_code & BME680_INT_ERROR_MASK)
{
case BME680_INT_BUSY: ...
case BME680_INT_READ_FAILED: ...
case BME680_I2C_BUSY: ...
case BME680_I2C_READ_FAILED: ...
...
}
switch (sensor->error_code & BME680_DRV_ERROR_MASK)
@ -258,58 +261,62 @@ The driver supports multiple BME680 sensors at the same time that are connected
First figure shows the configuration with only one sensor at I2C bus 0.
```
+-------------------------+ +--------+
| ESP8266 Bus 0 | | BME680 |
| GPIO 5 (SCL) +---->+ SCL |
| GPIO 4 (SDA) +-----+ SDA |
| | +--------+
+-------------------------+
+------------------+ +----------+
| ESP8266 / ESP32 | | BME680 |
| | | |
| GPIO 14 (SCL) ----> SCL |
| GPIO 13 (SDA) <---> SDA |
+------------------+ +----------+
```
Next figure shows the configuration with only one sensor at SPI bus using GPIO2 as CS signal.
Next figure shows the configuration with only one sensor at SPI bus.
```
+-------------------------+ +--------+
| Bus 1 | | BME680 |
| GPIO 12 (MISO) <------ SDO |
| GPIO 13 (MOSI) >-----> SDI |
| GPIO 14 (SCK) >-----> SCK |
| GPIO 2 (CS) >-----> CS |
+-------------------------+ +--------+
+------------------+ +----------+ +-----------------+ +----------+
| ESP8266 / ESP32 | | BME680 | | ESP32 | | BME680 |
| | | | | | | |
| GPIO 14 (SCK) ----> SCK | | GPIO 16 (SCK) ----> SCK |
| GPIO 13 (MOSI) ----> SDI | | GPIO 17 (MOSI)----> SDI |
| GPIO 12 (MISO) <---- SDO | | GPIO 18 (MISO)<---- SDO |
| GPIO 2 (CS) ----> CS | | GPIO 19 (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 which is used as CS signal of SPI bus 1 does not work correctly together with the BME680. Therefore, the user has to specify another GPIO pin as CS signal, e.g., GPIO2.
2. GPIO15 which is used as CS signal of SPI bus 1 on ESP8266 does not work correctly together with the BME680. Therefore, the user has to specify another GPIO pin as CS signal, e.g., GPIO2.
Next figure shows a possible configuration with two I2C buses. In that case, the sensors can have same or different I2C slave addresses.
```
+-------------------------+ +----------+
| ESP8266 Bus 0 | | BME680_1 |
| GPIO 5 (SCL) ------> SCL |
| GPIO 4 (SDA) ------- SDA |
| | +----------+
| Bus 1 | | BME680_2 |
| GPIO 14 (SCL) ------> SCL |
| GPIO 12 (SDA) ------- SDA |
+-------------------------+ +----------+
+------------------+ +----------+
| ESP8266 / ESP32 | | BME680_1 |
| | | |
| GPIO 14 (SCL) ----> SCL |
| GPIO 13 (SDA) <---> SDA |
| | +----------+
| | | BME680_2 |
| | | |
| GPIO 5 (SCL) ----> SCL |
| GPIO 4 (SDA) <---> SDA |
+------------------+ +----------+
```
Last figure shows a possible configuration using I2C bus 0 and SPI bus 1 at the same time.
```
+-------------------------+ +----------+
| ESP8266 Bus 0 | | BME680_1 |
| GPIO 5 (SCL) ------> SCL |
| GPIO 4 (SDA) ------- SDA |
| | +----------+
| Bus 1 | | BME680_2 |
| GPIO 12 (MISO) <------ SDO |
| GPIO 13 (MOSI) >-----> SDI |
| GPIO 14 (SCK) >-----> SCK |
| GPIO 2 (CS) >-----> CS |
+-------------------------+ +----------+
+------------------+ +----------+ +------------------+ +----------+
| ESP8266 | | BME680_1 | | ESP8266 | | BME680_1 |
| | | | | | | |
| GPIO 5 (SCL) ----> SCL | | GPIO 5 (SCL) ----> SCL |
| GPIO 4 (SDA) <---> SDA | | GPIO 4 (SDA) <---> SDA |
| | +----------+ | | +----------+
| | | BME680_2 | | | | BME680_2 |
| GPIO 14 (SCK) ----> SCK | | GPIO 16 (SCK) ----> SCK |
| GPIO 13 (MOSI) ----> SDI | | GPIO 17 (MOSI) ----> SDI |
| GPIO 12 (MISO) <---- SDO | | GPIO 18 (MISO) <---- SDO |
| GPIO 2 (CS) ----> CS | | GPIO 19 (CS) ----> CS |
+------------------+ +---------+ +------------------+ +----------+
```
Further configurations are possible, e.g., two sensors that are connected at the same I2C bus with different slave addresses.
@ -326,13 +333,13 @@ Dependent on the hardware configuration, the communication interface settings ha
// define I2C interface for BME680 sensors
#define I2C_BUS 0
#define I2C_SCL_PIN 5
#define I2C_SDA_PIN 4
#define I2C_SCL_PIN 14
#define I2C_SDA_PIN 13
#endif
```
### Main program
### Main programm
If I2C interfaces are used, they have to be initialized first.
@ -446,38 +453,55 @@ Once the measurement results are available, they can be fetched as fixed point o
## Full Example
```
// Uncomment to use SPI
/* -- use following constants to define the example mode ----------- */
// #define SPI_USED
#include "espressif/esp_common.h"
#include "esp/uart.h"
/* -- includes ----------------------------------------------------- */
#include "FreeRTOS.h"
#include "task.h"
#include "bme680.h"
// include communication interface driver
#include "esp/spi.h"
#include "i2c/i2c.h"
/* -- platform dependent definitions ------------------------------- */
// include BME680 driver
#include "bme680/bme680.h"
#ifdef ESP_PLATFORM // ESP32 (ESP-IDF)
#ifdef SPI_USED
// define SPI interface for BME680 sensors
#define SPI_BUS 1
#define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used
#else
// define I2C interface for BME680 sensors
#define I2C_BUS 0
#define I2C_SCL_PIN 5
#define I2C_SDA_PIN 4
#endif
// user task stack depth for ESP32
#define TASK_STACK_DEPTH 2048
static bme680_sensor_t* sensor;
// SPI interface definitions for ESP32
#define SPI_BUS HSPI_HOST
#define SPI_SCK_GPIO 16
#define SPI_MOSI_GPIO 17
#define SPI_MISO_GPIO 18
#define SPI_CS_GPIO 19
#else // ESP8266 (esp-open-rtos)
// user task stack depth for ESP8266
#define TASK_STACK_DEPTH 256
// SPI interface definitions for ESP8266
#define SPI_BUS 1
#define SPI_SCK_GPIO 14
#define SPI_MOSI_GPIO 13
#define SPI_MISO_GPIO 12
#define SPI_CS_GPIO 2 // GPIO 15, the default CS of SPI bus 1, can't be used
#endif // ESP_PLATFORM
// I2C interface defintions for ESP32 and ESP8266
#define I2C_BUS 0
#define I2C_SCL_PIN 14
#define I2C_SDA_PIN 13
#define I2C_FREQ I2C_FREQ_100K
/* -- user tasks --------------------------------------------------- */
static bme680_sensor_t* sensor = 0;
/*
* User task that triggers measurements of sensor every seconds. It uses
* function *vTaskDelay* to wait for measurement results. Busy waiting
* function *vTaskDelay* to wait for measurement results. Busy wating
* alternative is shown in comments
*/
void user_task(void *pvParameters)
@ -492,51 +516,58 @@ void user_task(void *pvParameters)
while (1)
{
// trigger the sensor to start one TPHG measurement cycle
bme680_force_measurement (sensor);
if (bme680_force_measurement (sensor))
{
// passive waiting until measurement results are available
vTaskDelay (duration);
// passive waiting until measurement results are available
vTaskDelay (duration);
// alternatively: busy waiting until measurement results are available
// while (bme680_is_measuring (sensor)) ;
// get the results and do something with them
if (bme680_get_results_float (sensor, &values))
printf("%.3f BME680 Sensor: %.2f °C, %.2f %%, %.2f hPa, %.2f Ohm\n",
(double)sdk_system_get_time()*1e-3,
values.temperature, values.humidity,
values.pressure, values.gas_resistance);
// alternatively: busy waiting until measurement results are available
// while (bme680_is_measuring (sensor)) ;
// get the results and do something with them
if (bme680_get_results_float (sensor, &values))
printf("%.3f BME680 Sensor: %.2f °C, %.2f %%, %.2f hPa, %.2f Ohm\n",
(double)sdk_system_get_time()*1e-3,
values.temperature, values.humidity,
values.pressure, values.gas_resistance);
}
// passive waiting until 1 second is over
vTaskDelayUntil(&last_wakeup, 1000 / portTICK_PERIOD_MS);
}
}
/* -- main program ------------------------------------------------- */
void user_init(void)
{
// Set UART Parameter
// Set UART Parameter.
uart_set_baud(0, 115200);
// Give the UART some time to settle
sdk_os_delay_us(500);
vTaskDelay(1);
/** -- MANDATORY PART -- */
#ifdef SPI_USED
// Init the sensor connected either to SPI.
sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO);
#else
// 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 the sensor connected either to I2C.
spi_bus_init (SPI_BUS, SPI_SCK_GPIO, SPI_MISO_GPIO, SPI_MOSI_GPIO);
// init the sensor connected to SPI_BUS with SPI_CS_GPIO as chip select.
sensor = bme680_init_sensor (SPI_BUS, 0, SPI_CS_GPIO);
#else // I2C
// Init all I2C bus interfaces at which BME680 sensors are connected
i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ);
// init the sensor with slave address BME680_I2C_ADDRESS_2 connected to I2C_BUS.
sensor = bme680_init_sensor (I2C_BUS, BME680_I2C_ADDRESS_2, 0);
#endif
#endif // SPI_USED
if (sensor)
{
// Create a task that uses the sensor
xTaskCreate(user_task, "user_task", 256, NULL, 2, NULL);
xTaskCreate(user_task, "user_task", TASK_STACK_DEPTH, NULL, 2, NULL);
/** -- OPTIONAL PART -- */
@ -550,6 +581,10 @@ void user_init(void)
// Change the heater profile 0 to 200 degree Celcius for 100 ms.
bme680_set_heater_profile (sensor, 0, 200, 100);
bme680_use_heater_profile (sensor, 0);
// Set ambient temperature to 10 degree Celsius
bme680_set_ambient_temperature (sensor, 10);
}
}
```

View file

@ -1,8 +1,11 @@
/*
* Driver for Bosch Sensortec BME680 digital temperature, humity, pressure and
* gas sensor connected to I2C or SPI
* Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure
* and gas sensor connected to I2C or SPI
*
* Part of esp-open-rtos [https://github.com/SuperHouse/esp-open-rtos]
* This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos)
* [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32
* and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux
* based systems using a wrapper library for ESP8266 functions.
*
* ---------------------------------------------------------------------------
*
@ -46,16 +49,9 @@
*/
#include <string.h>
#include <stdlib.h>
#include "FreeRTOS.h"
#include "task.h"
#include "espressif/esp_common.h"
#include "espressif/sdk_private.h"
#include "esp/spi.h"
#include "i2c/i2c.h"
#include "bme680_platform.h"
#include "bme680.h"
#if defined(BME680_DEBUG_LEVEL_2)
@ -276,12 +272,11 @@ static bool bme680_i2c_write (bme680_sensor_t* dev, uint8_t reg, uint8_t *da
static bool bme680_spi_read (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len);
static bool bme680_spi_write (bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len);
/** */
#define lsb_msb_to_type(t,b,o) (t)(((t)b[o+1] << 8) | b[o])
#define lsb_to_type(t,b,o) (t)(b[o])
bme680_sensor_t* bme680_init_sensor(uint8_t bus, uint8_t addr, uint8_t cs)
{
bme680_sensor_t* dev;
@ -291,7 +286,7 @@ bme680_sensor_t* bme680_init_sensor(uint8_t bus, uint8_t addr, uint8_t cs)
// init sensor data structure
dev->bus = bus;
dev->addr = addr;
dev->spi_cs_pin = cs;
dev->cs = cs;
dev->meas_started = false;
dev->meas_status = 0;
dev->settings.ambient_temperature = 0;
@ -303,12 +298,15 @@ bme680_sensor_t* bme680_init_sensor(uint8_t bus, uint8_t addr, uint8_t cs)
memset(dev->settings.heater_temperature, 0, sizeof(uint16_t)*10);
memset(dev->settings.heater_duration, 0, sizeof(uint16_t)*10);
if (!addr)
// if addr==0 then SPI is used and has to be initialized
if (!addr && !spi_device_init (bus, cs))
{
// SPI interface used
gpio_enable(dev->spi_cs_pin, GPIO_OUTPUT);
gpio_write (dev->spi_cs_pin, true);
error_dev ("Could not initialize SPI interface.", __FUNCTION__, dev);
free (dev);
return NULL;
}
if (!addr)
spi_semaphore_init();
// reset the sensor
if (!bme680_reset(dev))
@ -435,7 +433,6 @@ bool bme680_force_measurement (bme680_sensor_t* dev)
}
dev->meas_started = true;
dev->meas_start_tick = xTaskGetTickCount (); // system time in RTOS ticks
dev->meas_status = 0;
debug_dev ("Started measurement at %.3f.", __FUNCTION__, dev,
@ -817,10 +814,7 @@ bool bme680_set_ambient_temperature (bme680_sensor_t* dev, int16_t ambient)
// set ambient temperature configuration
dev->settings.ambient_temperature = ambient; // degree Celsius
// update all valid heater profiles
// takes 894 us for only one defined profile and 1585 us for 10 defined profiles
uint8_t data[10];
for (int i = 0; i < BME680_HEATER_PROFILES; i++)
{
@ -830,17 +824,6 @@ bool bme680_set_ambient_temperature (bme680_sensor_t* dev, int16_t ambient)
if (!bme680_write_reg(dev, BME680_REG_RES_HEAT_BASE, data, 10))
return false;
/*
// takes 346 us for only one defined profile and 3316 us for 10 defined profiles
for (int i = 0; i < BME680_HEATER_PROFILES; i++)
if (dev->settings.heater_temperature[i])
{
uint8_t heat_res = bme680_heater_resistance(dev, dev->settings.heater_temperature[i]);
if (!bme680_write_reg(dev, BME680_REG_RES_HEAT_BASE+i, &heat_res, 1))
return false;
}
*/
debug_dev ("Setting heater ambient temperature done: ambient=%d",
__FUNCTION__, dev, dev->settings.ambient_temperature);
@ -1110,16 +1093,16 @@ static bool bme680_get_raw_data(bme680_sensor_t *dev, bme680_raw_data_t* raw_dat
return false;
}
// test whether there are new data
dev->meas_status = raw[0];
if (dev->meas_status & BME680_MEASURING_BITS)
if (dev->meas_status & BME680_MEASURING_BITS &&
!(dev->meas_status & BME680_NEW_DATA_BITS))
{
debug_dev ("Measurement is still running.", __FUNCTION__, dev);
dev->error_code = BME680_MEAS_STILL_RUNNING;
return false;
}
// test whether there are new data
if (!(dev->meas_status & BME680_NEW_DATA_BITS))
else if (!(dev->meas_status & BME680_NEW_DATA_BITS))
{
debug_dev ("No new data.", __FUNCTION__, dev);
dev->error_code = BME680_NO_NEW_DATA;
@ -1242,17 +1225,6 @@ static void bme680_delay_ms(uint32_t period)
}
#define BME680_SPI_BUF_SIZE 64 // SPI register data buffer size of ESP866
static const spi_settings_t bus_settings = {
.mode = SPI_MODE3,
.freq_divider = SPI_FREQ_DIV_1M,
.msb = true,
.minimal_pins = false,
.endianness = SPI_LITTLE_ENDIAN
};
static bool bme680_read_reg(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len)
{
if (!dev || !data) return false;
@ -1270,6 +1242,8 @@ static bool bme680_write_reg(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, u
: bme680_spi_write (dev, reg, data, len);
}
#define BME680_SPI_BUF_SIZE 64 // SPI register data buffer size of ESP866
#define BME680_REG_SWITCH_MEM_PAGE BME680_REG_STATUS
#define BME680_BIT_SWITCH_MEM_PAGE_0 0x00
#define BME680_BIT_SWITCH_MEM_PAGE_1 0x10
@ -1288,11 +1262,9 @@ static bool bme680_spi_set_mem_page (bme680_sensor_t* dev, uint8_t reg)
return false;
}
// sdk_os_delay_us (100);
return true;
}
static bool bme680_spi_read(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len)
{
if (!dev || !data) return false;
@ -1306,19 +1278,20 @@ static bool bme680_spi_read(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, ui
return false;
}
spi_semaphore_take ();
// set mem page first
if (!bme680_spi_set_mem_page (dev, reg))
{
error_dev ("Error on read from SPI slave on bus 1. Could not set mem page.",
__FUNCTION__, dev);
spi_semaphore_give ();
return false;
}
}
reg &= 0x7f;
reg |= 0x80;
spi_settings_t old_settings;
static uint8_t mosi[BME680_SPI_BUF_SIZE];
static uint8_t miso[BME680_SPI_BUF_SIZE];
@ -1327,33 +1300,26 @@ static bool bme680_spi_read(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, ui
mosi[0] = reg;
spi_get_settings(dev->bus, &old_settings);
spi_set_settings(dev->bus, &bus_settings);
gpio_write(dev->spi_cs_pin, false);
size_t transfered = spi_transfer (dev->bus, (const void*)mosi, (void*)miso, len+1, SPI_8BIT);
gpio_write(dev->spi_cs_pin, true);
spi_set_settings(dev->bus, &old_settings);
if (!transfered)
if (!spi_transfer_pf (dev->bus, dev->cs, mosi, miso, len+1))
{
error_dev ("Could not read data from SPI", __FUNCTION__, dev);
dev->error_code |= BME680_SPI_READ_FAILED;
spi_semaphore_give ();
return false;
}
spi_semaphore_give ();
// shift data one by left, first byte received while sending register address is invalid
for (int i=0; i < len; i++)
data[i] = miso[i+1];
# ifdef BME680_DEBUG_LEVEL_2
#ifdef BME680_DEBUG_LEVEL_2
printf("BME680 %s: read the following bytes: ", __FUNCTION__);
printf("%0x ", reg);
for (int i=0; i < len; i++)
printf("%0x ", data[i]);
printf("\n");
# endif
#endif
return true;
}
@ -1374,11 +1340,14 @@ static bool bme680_spi_write(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, u
return false;
}
spi_semaphore_take ();
// set mem page first if not mem page register is used
if (reg != BME680_REG_STATUS && !bme680_spi_set_mem_page (dev, reg))
{
error_dev ("Error on write from SPI slave on bus 1. Could not set mem page.",
__FUNCTION__, dev);
spi_semaphore_give ();
return false;
}
@ -1391,34 +1360,26 @@ static bool bme680_spi_write(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, u
for (int i = 0; i < len; i++)
mosi[i+1] = data[i];
# ifdef BME680_DEBUG_LEVEL_2
#ifdef BME680_DEBUG_LEVEL_2
printf("BME680 %s: Write the following bytes: ", __FUNCTION__);
for (int i = 0; i < len+1; i++)
printf("%0x ", mosi[i]);
printf("\n");
# endif
#endif
spi_settings_t old_settings;
spi_get_settings(dev->bus, &old_settings);
spi_set_settings(dev->bus, &bus_settings);
gpio_write(dev->spi_cs_pin, false);
size_t transfered = spi_transfer (dev->bus, (const void*)mosi, NULL, len+1, SPI_8BIT);
gpio_write(dev->spi_cs_pin, true);
spi_set_settings(dev->bus, &old_settings);
if (!transfered)
if (!spi_transfer_pf (dev->bus, dev->cs, mosi, NULL, len+1))
{
error_dev ("Could not write data to SPI.", __FUNCTION__, dev);
dev->error_code |= BME680_SPI_WRITE_FAILED;
spi_semaphore_give ();
return false;
}
spi_semaphore_give ();
return true;
}
static bool bme680_i2c_read(bme680_sensor_t* dev, uint8_t reg, uint8_t *data, uint16_t len)
{
if (!dev || !data) return false;

View file

@ -1,14 +1,17 @@
/*
* Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure and
* gas sensor connected to I2C or SPI
* Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure
* and gas sensor connected to I2C or SPI
*
* Part of esp-open-rtos [https://github.com/SuperHouse/esp-open-rtos]
* This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos)
* [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32
* and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux
* based systems using a wrapper library for ESP8266 functions.
*
* ---------------------------------------------------------------------------
*
* The BSD License (3-clause license)
*
* Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht]
* Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht)
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@ -41,12 +44,13 @@
#ifndef __BME680_H__
#define __BME680_H__
#include "bme680/bme680_types.h"
// Uncomment one of the following defines to enable debug output
// #define BME680_DEBUG_LEVEL_1 // only error messages
// #define BME680_DEBUG_LEVEL_2 // debug and error messages
#include "bme680_types.h"
#include "bme680_platform.h"
// BME680 addresses
#define BME680_I2C_ADDRESS_1 0x76 // SDO pin is low
#define BME680_I2C_ADDRESS_2 0x77 // SDO pin is high
@ -144,8 +148,7 @@ extern "C"
* @param cs SPI CS GPIO, ignored for I2C
* @return pointer to sensor data structure, or NULL on error
*/
bme680_sensor_t* bme680_init_sensor (uint8_t bus, uint8_t addr, uint8_t cs_pin);
bme680_sensor_t* bme680_init_sensor (uint8_t bus, uint8_t addr, uint8_t cs);
/**
* @brief Force one single TPHG measurement

View file

@ -0,0 +1,112 @@
/*
* Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure
* and gas sensor connected to I2C or SPI
*
* This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos)
* [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32
* and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux
* based systems using a wrapper library for ESP8266 functions.
*
* ---------------------------------------------------------------------------
*
* 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.
*/
/**
* Platform file: platform specific definitions, includes and functions
*/
#ifndef __BME680_PLATFORM_H__
#define __BME680_PLATFORM_H__
#if !defined(ESP_OPEN_RTOS)
#define ESP_OPEN_RTOS 1
#endif
#ifdef ESP_OPEN_RTOS // ESP8266
// platform specific includes
#include "FreeRTOS.h"
#include "task.h"
#include "espressif/esp_common.h"
#include "espressif/sdk_private.h"
#include "esp/uart.h"
#include "esp/spi.h"
#include "i2c/i2c.h"
// platform specific definitions
#define spi_semaphore_init()
#define spi_semaphore_take()
#define spi_semaphore_give()
// platform specific SPI functions
#define spi_bus_init(bus,sck,miso,mosi) // not needed on ESP8266
static const spi_settings_t bus_settings = {
.mode = SPI_MODE0,
.freq_divider = SPI_FREQ_DIV_1M,
.msb = true,
.minimal_pins = false,
.endianness = SPI_LITTLE_ENDIAN
};
inline static bool spi_device_init (uint8_t bus, uint8_t cs)
{
gpio_enable(cs, GPIO_OUTPUT);
gpio_write (cs, true);
return true;
}
inline static size_t spi_transfer_pf(uint8_t bus, uint8_t cs, const uint8_t *mosi, uint8_t *miso, uint16_t len)
{
spi_settings_t old_settings;
spi_get_settings(bus, &old_settings);
spi_set_settings(bus, &bus_settings);
gpio_write(cs, false);
size_t transfered = spi_transfer (bus, (const void*)mosi, (void*)miso, len, SPI_8BIT);
gpio_write(cs, true);
spi_set_settings(bus, &old_settings);
return transfered;
}
#endif // ESP_OPEN_RTOS
#endif // __BME680_PLATFORM_H__

View file

@ -1,14 +1,17 @@
/*
* Driver for Bosch Sensortec BME680 digital temperature, humity, pressure and
* gas sensor connected to I2C or SPI
* Driver for Bosch Sensortec BME680 digital temperature, humidity, pressure
* and gas sensor connected to I2C or SPI
*
* Part of esp-open-rtos [https://github.com/SuperHouse/esp-open-rtos]
* This driver is for the usage with the ESP8266 and FreeRTOS (esp-open-rtos)
* [https://github.com/SuperHouse/esp-open-rtos]. It is also working with ESP32
* and ESP-IDF [https://github.com/espressif/esp-idf.git] as well as Linux
* based systems using a wrapper library for ESP8266 functions.
*
* ---------------------------------------------------------------------------
*
* The BSD License (3-clause license)
*
* Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht]
* Copyright (c) 2017 Gunar Schorcht (https://github.com/gschorcht)
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
@ -173,14 +176,14 @@ typedef struct {
uint8_t bus; // I2C = x, SPI = 1
uint8_t addr; // I2C = slave address, SPI = 0
uint8_t spi_cs_pin; // GPIO used as SPI CS
uint8_t cs; // ESP8266, ESP32: GPIO used as SPI CS
// __linux__: device index
bool meas_started; // indicates whether measurement started
uint32_t meas_start_tick; // measurement start time in RTOS ticks
uint8_t meas_status; // last sensor status (for internal use only)
bme680_settings_t settings; // sensor settings
bme680_calib_data_t calib_data; // calibration data of the sensor
bme680_settings_t settings; // sensor settings
bme680_calib_data_t calib_data; // calibration data of the sensor
} bme680_sensor_t;

View file

@ -2,6 +2,7 @@
# expected anyone using bme680 driver includes it as 'bme680/bme680.h'
INC_DIRS += $(bme680_ROOT)..
INC_DIRS += $(bme680_ROOT)
# args for passing into compile rule generation
bme680_SRC_DIR = $(bme680_ROOT)