- Delaying and repeating i2c operation automatically when i2c interface is busy removed. User has to deal with concurrency using semaphores.
- GPIO_ID_PIN macros removed - Soft reset mechanism of SHT3x does not work when sensor is in any measurement mode. Therefore, it does not abort initialization procedure anymore - typos - changes to use the same source code with ESP8266 (esp-open-rtos) and ESP32 (ESP-IDF)
This commit is contained in:
parent
c3ae04c93f
commit
ca0b5da905
7 changed files with 254 additions and 110 deletions
|
@ -1,6 +1,8 @@
|
|||
# Driver for **SHT3x** digital **temperature and humidity sensor**
|
||||
|
||||
This driver is written for usage with the ESP8266 and FreeRTOS using the I2C interface driver. It supports multiple SHT3x sensors connected to the same or different I2C interfaces.
|
||||
The driver is for the usage with the ESP8266 and [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) 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
|
||||
|
||||
|
@ -79,8 +81,8 @@ Before using the SHT3x driver, function ```i2c_init``` needs to be called for ea
|
|||
#include "sht3x/sht3x.h"
|
||||
...
|
||||
#define I2C_BUS 0
|
||||
#define I2C_SCL_PIN GPIO_ID_PIN((5))
|
||||
#define I2C_SDA_PIN GPIO_ID_PIN((4))
|
||||
#define I2C_SCL_PIN 14
|
||||
#define I2C_SDA_PIN 13
|
||||
|
||||
...
|
||||
i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ_100K)
|
||||
|
@ -232,25 +234,44 @@ if (!sht3x_get_results (sensor, &values))
|
|||
## Full Example
|
||||
|
||||
```
|
||||
#include "espressif/esp_common.h"
|
||||
#include "esp/uart.h"
|
||||
/* -- use following constants to define the example mode ----------- */
|
||||
|
||||
#include "FreeRTOS.h"
|
||||
#include "task.h"
|
||||
// #define SINGLE_SHOT_LOW_LEVEL
|
||||
// #define SINGLE_SHOT_HIGH_LEVEL
|
||||
|
||||
// include SHT3x driver
|
||||
#include "sht3x/sht3x.h"
|
||||
/* -- includes ----------------------------------------------------- */
|
||||
|
||||
// define I2C interfaces at which SHTx3 sensors are connected
|
||||
#include "sht3x.h"
|
||||
|
||||
/* -- platform dependent definitions ------------------------------- */
|
||||
|
||||
#ifdef ESP_PLATFORM // ESP32 (ESP-IDF)
|
||||
|
||||
// user task stack depth for ESP32
|
||||
#define TASK_STACK_DEPTH 2048
|
||||
|
||||
#else // ESP8266 (esp-open-rtos)
|
||||
|
||||
// user task stack depth for ESP8266
|
||||
#define TASK_STACK_DEPTH 256
|
||||
|
||||
#endif // ESP_PLATFORM
|
||||
|
||||
// I2C interface defintions for ESP32 and ESP8266
|
||||
#define I2C_BUS 0
|
||||
#define I2C_SCL_PIN GPIO_ID_PIN((5))
|
||||
#define I2C_SDA_PIN GPIO_ID_PIN((4))
|
||||
#define I2C_SCL_PIN 14
|
||||
#define I2C_SDA_PIN 13
|
||||
#define I2C_FREQ I2C_FREQ_100K
|
||||
|
||||
/* -- user tasks --------------------------------------------------- */
|
||||
|
||||
static sht3x_sensor_t* sensor; // sensor device data structure
|
||||
|
||||
#if defined(SINGLE_SHOT_HIGH_LEVEL)
|
||||
/*
|
||||
* User task that triggers a measurement every 5 seconds. Due to
|
||||
* power efficiency reasons, it uses the SHT3x *sht3x_single_shot*.
|
||||
* User task that triggers a measurement every 5 seconds. Due to power
|
||||
* efficiency reasons it uses *single shot* mode. In this example it uses the
|
||||
* high level function *sht3x_measure* to perform one measurement in each cycle.
|
||||
*/
|
||||
void user_task (void *pvParameters)
|
||||
{
|
||||
|
@ -258,10 +279,36 @@ void user_task (void *pvParameters)
|
|||
float humidity;
|
||||
|
||||
TickType_t last_wakeup = xTaskGetTickCount();
|
||||
|
||||
|
||||
while (1)
|
||||
{
|
||||
// perform one measurement and do something with the results
|
||||
if (sht3x_measure (sensor, &temperature, &humidity))
|
||||
printf("%.3f SHT3x Sensor: %.2f °C, %.2f %%\n",
|
||||
(double)sdk_system_get_time()*1e-3, temperature, humidity);
|
||||
|
||||
// wait until 5 seconds are over
|
||||
vTaskDelayUntil(&last_wakeup, 5000 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
|
||||
#elif defined(SINGLE_SHOT_LOW_LEVEL)
|
||||
/*
|
||||
* User task that triggers a measurement every 5 seconds. Due to power
|
||||
* efficiency reasons it uses *single shot* mode. In this example it starts the
|
||||
* measurement, waits for the results and fetches the results using separate
|
||||
* functions
|
||||
*/
|
||||
void user_task (void *pvParameters)
|
||||
{
|
||||
float temperature;
|
||||
float humidity;
|
||||
|
||||
TickType_t last_wakeup = xTaskGetTickCount();
|
||||
|
||||
// get the measurement duration for high repeatability;
|
||||
uint8_t duration = sht3x_get_measurement_duration(sht3x_high);
|
||||
|
||||
|
||||
while (1)
|
||||
{
|
||||
// Trigger one measurement in single shot mode with high repeatability.
|
||||
|
@ -281,29 +328,60 @@ void user_task (void *pvParameters)
|
|||
}
|
||||
}
|
||||
|
||||
#else // PERIODIC MODE
|
||||
/*
|
||||
* User task that fetches latest measurement results of sensor every 2
|
||||
* seconds. It starts the SHT3x in periodic mode with 1 measurements per
|
||||
* second (*sht3x_periodic_1mps*).
|
||||
*/
|
||||
void user_task (void *pvParameters)
|
||||
{
|
||||
float temperature;
|
||||
float humidity;
|
||||
|
||||
// Start periodic measurements with 1 measurement per second.
|
||||
sht3x_start_measurement (sensor, sht3x_periodic_1mps, sht3x_high);
|
||||
|
||||
// Wait until first measurement is ready (constant time of at least 30 ms
|
||||
// or the duration returned from *sht3x_get_measurement_duration*).
|
||||
vTaskDelay (sht3x_get_measurement_duration(sht3x_high));
|
||||
|
||||
TickType_t last_wakeup = xTaskGetTickCount();
|
||||
|
||||
while (1)
|
||||
{
|
||||
// Get the values and do something with them.
|
||||
if (sht3x_get_results (sensor, &temperature, &humidity))
|
||||
printf("%.3f SHT3x Sensor: %.2f °C, %.2f %%\n",
|
||||
(double)sdk_system_get_time()*1e-3, temperature, humidity);
|
||||
|
||||
// Wait until 2 seconds (cycle time) are over.
|
||||
vTaskDelayUntil(&last_wakeup, 2000 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* -- main program ------------------------------------------------- */
|
||||
|
||||
void user_init(void)
|
||||
{
|
||||
// Set UART Parameter.
|
||||
uart_set_baud(0, 115200);
|
||||
|
||||
// Give the UART some time to settle.
|
||||
sdk_os_delay_us(500);
|
||||
// Give the UART some time to settle
|
||||
vTaskDelay(1);
|
||||
|
||||
// Init I2C bus interfaces at which SHT3x sensors are connected
|
||||
// (different busses are possible).
|
||||
i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ_100K);
|
||||
i2c_init(I2C_BUS, I2C_SCL_PIN, I2C_SDA_PIN, I2C_FREQ);
|
||||
|
||||
// Create the sensors.
|
||||
// Create the sensors, multiple sensors are possible.
|
||||
if ((sensor = sht3x_init_sensor (I2C_BUS, SHT3x_ADDR_2)))
|
||||
{
|
||||
// Create a user task that uses the sensors.
|
||||
xTaskCreate(user_task, "user_task", 256, NULL, 2, 0);
|
||||
xTaskCreate(user_task, "user_task", TASK_STACK_DEPTH, NULL, 2, 0);
|
||||
}
|
||||
|
||||
// That's it.
|
||||
}
|
||||
```
|
||||
|
||||
## Further Examples
|
||||
|
||||
See also the examples in the examples directory [examples directory](../../examples/sht3x/README.md).
|
||||
|
|
|
@ -2,6 +2,7 @@
|
|||
|
||||
# expected anyone using SHT3x driver includes it as 'sht3x/sht3x.h'
|
||||
INC_DIRS += $(sht3x_ROOT)..
|
||||
INC_DIRS += $(sht3x_ROOT)
|
||||
|
||||
# args for passing into compile rule generation
|
||||
sht3x_SRC_DIR = $(sht3x_ROOT)
|
||||
|
|
|
@ -2,13 +2,16 @@
|
|||
* Driver for Sensirion SHT3x digital temperature and humidity sensor
|
||||
* connected to I2C
|
||||
*
|
||||
* Part of 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
|
||||
|
@ -38,23 +41,11 @@
|
|||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Driver for Sensirion SHT3x digital temperature and humity sensor
|
||||
* connected to I2C
|
||||
*
|
||||
* Part of esp-open-rtos
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "sht3x.h"
|
||||
|
||||
#include "FreeRTOS.h"
|
||||
#include "task.h"
|
||||
|
||||
#include "espressif/esp_common.h"
|
||||
#include "espressif/sdk_private.h"
|
||||
|
||||
#define SHT3x_STATUS_CMD 0xF32D
|
||||
#define SHT3x_CLEAR_STATUS_CMD 0x3041
|
||||
#define SHT3x_RESET_CMD 0x30A2
|
||||
|
@ -139,12 +130,10 @@ sht3x_sensor_t* sht3x_init_sensor(uint8_t bus, uint8_t addr)
|
|||
|
||||
uint16_t status;
|
||||
|
||||
// reset the sensor
|
||||
// try to reset the sensor
|
||||
if (!sht3x_reset(dev))
|
||||
{
|
||||
error_dev ("could not reset the sensor", __FUNCTION__, dev);
|
||||
free(dev);
|
||||
return NULL;
|
||||
debug_dev ("could not reset the sensor", __FUNCTION__, dev);
|
||||
}
|
||||
|
||||
// check again the status after clear status command
|
||||
|
@ -325,13 +314,7 @@ static bool sht3x_send_command(sht3x_sensor_t* dev, uint16_t cmd)
|
|||
|
||||
debug_dev ("send command MSB=%02x LSB=%02x", __FUNCTION__, dev, data[0], data[1]);
|
||||
|
||||
int err;
|
||||
int count = 10;
|
||||
|
||||
// in case i2c is busy, try to write up to ten ticks (normally 100 ms)
|
||||
// tested with a task that is disturbing by using i2c bus almost all the time
|
||||
while ((err=i2c_slave_write(dev->bus, dev->addr, 0, data, 2)) == -EBUSY && count--)
|
||||
vTaskDelay (1);
|
||||
int err = i2c_slave_write(dev->bus, dev->addr, 0, data, 2);
|
||||
|
||||
if (err)
|
||||
{
|
||||
|
@ -339,21 +322,14 @@ static bool sht3x_send_command(sht3x_sensor_t* dev, uint16_t cmd)
|
|||
error_dev ("i2c error %d on write command %02x", __FUNCTION__, dev, err, cmd);
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
static bool sht3x_read_data(sht3x_sensor_t* dev, uint8_t *data, uint32_t len)
|
||||
{
|
||||
if (!dev) return false;
|
||||
|
||||
int err;
|
||||
int count = 10;
|
||||
|
||||
// in case i2c is busy, try to read up to ten ticks (normally 100 ms)
|
||||
while ((err=i2c_slave_read(dev->bus, dev->addr, 0, data, len)) == -EBUSY && count--)
|
||||
vTaskDelay (1);
|
||||
int err = i2c_slave_read(dev->bus, dev->addr, 0, data, len);
|
||||
|
||||
if (err)
|
||||
{
|
||||
|
@ -368,7 +344,7 @@ static bool sht3x_read_data(sht3x_sensor_t* dev, uint8_t *data, uint32_t len)
|
|||
for (int i=0; i < len; i++)
|
||||
printf("%02x ", data[i]);
|
||||
printf("\n");
|
||||
# endif
|
||||
# endif // ifdef SHT3x_DEBUG_LEVEL_2
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -2,13 +2,16 @@
|
|||
* Driver for Sensirion SHT3x digital temperature and humidity sensor
|
||||
* connected to I2C
|
||||
*
|
||||
* Part of 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
|
||||
|
@ -38,20 +41,18 @@
|
|||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#ifndef DRIVER_SHT3x_H_
|
||||
#define DRIVER_SHT3x_H_
|
||||
|
||||
#include "stdint.h"
|
||||
#include "stdbool.h"
|
||||
|
||||
#include "FreeRTOS.h"
|
||||
|
||||
#include "i2c/i2c.h"
|
||||
#ifndef __SHT3x_H__
|
||||
#define __SHT3x_H__
|
||||
|
||||
// Uncomment to enable debug output
|
||||
// #define SHT3x_DEBUG_LEVEL_1 // only error messages
|
||||
// #define SHT3x_DEBUG_LEVEL_2 // error and debug messages
|
||||
|
||||
#include "stdint.h"
|
||||
#include "stdbool.h"
|
||||
|
||||
#include "sht3x_platform.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
@ -276,4 +277,4 @@ bool sht3x_get_results (sht3x_sensor_t* dev,
|
|||
}
|
||||
#endif
|
||||
|
||||
#endif /* DRIVER_SHT3x_H_ */
|
||||
#endif /* __SHT3x_H__ */
|
||||
|
|
70
extras/sht3x/sht3x_platform.h
Normal file
70
extras/sht3x/sht3x_platform.h
Normal file
|
@ -0,0 +1,70 @@
|
|||
/*
|
||||
* Driver for Sensirion SHT3x digital temperature and humidity sensor
|
||||
* connected to I2C
|
||||
*
|
||||
* 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 __SHT3x_PLATFORM_H__
|
||||
#define __SHT3x_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 "i2c/i2c.h"
|
||||
|
||||
#endif // ESP_OPEN_RTOS
|
||||
|
||||
#endif // __SHT3x_PLATFORM_H__
|
Loading…
Add table
Add a link
Reference in a new issue