From 222aafaf0579a5fab34c97120710eefd1d486e23 Mon Sep 17 00:00:00 2001 From: David Douard Date: Tue, 27 Apr 2021 09:55:38 +0200 Subject: [PATCH] mhz19b: add support for the MH-Z19B CO2 sensor (#179) * mhz19b: add support for the MH-Z19B CO2 sensor * mhz19b: brought to repo standard, add docs, fix build on ESP-IDF < 4.4 * mhz19b: fix build for esp8266 * mhz19b: fix build for ESP8266 * mhz19b: fix build for ESP-IDF v < 4.0 * mhz19b: fix example Co-authored-by: UncleRus --- README.md | 3 + components/mhz19b/CMakeLists.txt | 6 + components/mhz19b/LICENSE | 26 +++ components/mhz19b/README.md | 62 +++++++ components/mhz19b/component.mk | 2 + components/mhz19b/mhz19b.c | 269 ++++++++++++++++++++++++++++ components/mhz19b/mhz19b.h | 257 ++++++++++++++++++++++++++ docs/source/groups/mhz19b.rst | 7 + docs/source/index.rst | 1 + examples/mhz19b/CMakeLists.txt | 8 + examples/mhz19b/Makefile | 6 + examples/mhz19b/main/CMakeLists.txt | 2 + examples/mhz19b/main/component.mk | 1 + examples/mhz19b/main/main.c | 52 ++++++ 14 files changed, 702 insertions(+) create mode 100644 components/mhz19b/CMakeLists.txt create mode 100644 components/mhz19b/LICENSE create mode 100644 components/mhz19b/README.md create mode 100644 components/mhz19b/component.mk create mode 100644 components/mhz19b/mhz19b.c create mode 100644 components/mhz19b/mhz19b.h create mode 100644 docs/source/groups/mhz19b.rst create mode 100644 examples/mhz19b/CMakeLists.txt create mode 100644 examples/mhz19b/Makefile create mode 100644 examples/mhz19b/main/CMakeLists.txt create mode 100644 examples/mhz19b/main/component.mk create mode 100644 examples/mhz19b/main/main.c diff --git a/README.md b/README.md index 692e047c..f3bcc582 100644 --- a/README.md +++ b/README.md @@ -141,6 +141,7 @@ See [GitHub examples](https://github.com/UncleRus/esp-idf-lib/tree/master/exampl |----------------|-------------------------------------------------------------------------|---------|---------|--------------- | **sgp40** | SGP40 Indoor Air Quality Sensor for VOC Measurements | BSD | Yes | Yes | **ccs811** | Driver for AMS CCS811 digital gas sensor | BSD | Yes | Yes +| **mhz19b** | Driver for MH-Z19B NDIR CO2 sensor | BSD | Yes | *No* ### ADC/DAC @@ -234,3 +235,5 @@ See [GitHub examples](https://github.com/UncleRus/esp-idf-lib/tree/master/exampl - [Lucio Tarantino](https://github.com/dianlight), developer of ADS111x driver - [Julian Dörner](https://github.com/juliandoerner), developer of TSL2591 driver - [FastLED community](https://github.com/FastLED), developers of `lib8tion`, `color` and `noise` libraries +- [Erriez](https://github.com/Erriez), developer of MH-Z19B driver +- [David Douard](https://github.com/douardda), developer of MH-Z19B driver diff --git a/components/mhz19b/CMakeLists.txt b/components/mhz19b/CMakeLists.txt new file mode 100644 index 00000000..1db6b163 --- /dev/null +++ b/components/mhz19b/CMakeLists.txt @@ -0,0 +1,6 @@ +set(COMPONENT_SRCDIRS .) +set(COMPONENT_ADD_INCLUDEDIRS .) + +set(COMPONENT_REQUIRES log esp_idf_lib_helpers) + +register_component() diff --git a/components/mhz19b/LICENSE b/components/mhz19b/LICENSE new file mode 100644 index 00000000..67ac901b --- /dev/null +++ b/components/mhz19b/LICENSE @@ -0,0 +1,26 @@ +Copyright (C) 2021 David Douard + +Redistribution and use in source and binary forms, with or woithout +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 itscontributors +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. diff --git a/components/mhz19b/README.md b/components/mhz19b/README.md new file mode 100644 index 00000000..555b9375 --- /dev/null +++ b/components/mhz19b/README.md @@ -0,0 +1,62 @@ +# Driver for the MH-Z19B NDIR CO2 sensor + +This driver is heavily inspired from [Erriez MH-Z19B CO2 sensor library for +Arduino](https://github.com/Erriez/ErriezMHZ19B). + +It uses an UART serial port to communicate with the sensor. Since the UART must +configured a specific way (9600 8N1), the `mhz19b_init()` takes care of configuring it. +It will however not start detecting/reading from the sensor. This must be done. Typical +usage would be: + + +```C +[...] +#include "esp_log.h" +#include "mhz19b.h" + +#define MHZ19B_TX 12 +#define MHZ19B_RX 13 + +void app_main(void) +{ + int16_t co2; + mhz19b_dev_t dev; + char version[6]; + uint16_t range; + bool autocal; + + mhz19b_init(&dev, UART_NUM_1, MHZ19B_TX, MHZ19B_RX); + + while (!mhz19b_detect(&dev)) + { + ESP_LOGI(TAG, "MHZ-19B not detected, waiting..."); + vTaskDelay(1000 / portTICK_RATE_MS); + } + + mhz19b_get_version(&dev, version, 5); + ESP_LOGI(TAG, "MHZ-19B firmware version: %s", version); + ESP_LOGI(TAG, "MHZ-19B set range and autocal"); + + mhz19b_set_range(&dev, MHZ19B_RANGE_5000); + mhz19b_set_auto_calibration(&dev, false); + + mhz19b_get_range(&dev, &range); + ESP_LOGI(TAG, " range: %d", range); + + mhz19b_get_auto_calibration(&dev, &autocal); + ESP_LOGI(TAG, " autocal: %s", autocal ? "ON" : "OFF"); + + while (mhz19b_is_warming_up(&dev)) + { + ESP_LOGI(TAG, "MHZ-19B is warming up"); + vTaskDelay(1000 / portTICK_RATE_MS); + } + + while (1) { + mhz19b_read_CO2(&dev, &co2); + ESP_LOGI(TAG, "CO2: %d", co2); + vTaskDelay(5000 / portTICK_RATE_MS); + } +} + +``` diff --git a/components/mhz19b/component.mk b/components/mhz19b/component.mk new file mode 100644 index 00000000..64d93099 --- /dev/null +++ b/components/mhz19b/component.mk @@ -0,0 +1,2 @@ +COMPONENT_ADD_INCLUDEDIRS = . +COMPONENT_DEPENDS = log diff --git a/components/mhz19b/mhz19b.c b/components/mhz19b/mhz19b.c new file mode 100644 index 00000000..734a67d6 --- /dev/null +++ b/components/mhz19b/mhz19b.c @@ -0,0 +1,269 @@ +/** + * @file mhz19b.c + * + * ESP-IDF driver for MH-Z19B NDIR CO2 sensor connected to UART + * + * Inspired from https://github.com/Erriez/ErriezMHZ19B + * + * Copyright (C) 2020 Erriez + * Copyright (C) 2021 David Douard + * + * BSD Licensed as described in the file LICENSE + */ +#include +#include +#include +#include +#include +#include + +#include "mhz19b.h" + +static const char *TAG = "mhz19b"; + +#define CHECK(x) do { esp_err_t __; if ((__ = x) != ESP_OK) return __; } while (0) +#define CHECK_ARG(VAL) do { if (!(VAL)) return ESP_ERR_INVALID_ARG; } while (0) + +esp_err_t mhz19b_init(mhz19b_dev_t *dev, uart_port_t uart_port, gpio_num_t tx_gpio, gpio_num_t rx_gpio) +{ + CHECK_ARG(dev); + + uart_config_t uart_config = { + .baud_rate = 9600, + .data_bits = UART_DATA_8_BITS, + .parity = UART_PARITY_DISABLE, + .stop_bits = UART_STOP_BITS_1, + .flow_ctrl = UART_HW_FLOWCTRL_DISABLE, +#if ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(4, 4, 0) + .source_clk = UART_SCLK_APB, +#endif + }; + CHECK(uart_driver_install(uart_port, MHZ19B_SERIAL_BUF_LEN * 2, 0, 0, NULL, 0)); + CHECK(uart_param_config(uart_port, &uart_config)); +#if HELPER_TARGET_IS_ESP32 + CHECK(uart_set_pin(uart_port, tx_gpio, rx_gpio, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE)); +#endif + + dev->uart_port = uart_port; + // buffer for the incoming data + dev->buf = malloc(MHZ19B_SERIAL_BUF_LEN); + if (!dev->buf) + return ESP_ERR_NO_MEM; + dev->last_value = -1; + dev->last_ts = esp_timer_get_time(); + return ESP_OK; +} + +esp_err_t mhz19b_free(mhz19b_dev_t *dev) +{ + CHECK_ARG(dev && dev->buf); + + free(dev->buf); + dev->buf = NULL; + return ESP_OK; +} + +bool mhz19b_detect(mhz19b_dev_t *dev) +{ + CHECK_ARG(dev); + + uint16_t range; + // Check valid PPM range + if ((mhz19b_get_range(dev, &range) == ESP_OK) && (range > 0)) + return true; + + // Sensor not detected, or invalid range returned + // Try recover by calling setRange(MHZ19B_RANGE_5000); + return false; +} + +bool mhz19b_is_warming_up(mhz19b_dev_t *dev, bool smart_warming_up) +{ + CHECK_ARG(dev); + + // Wait at least 3 minutes after power-on + if (esp_timer_get_time() < MHZ19B_WARMING_UP_TIME_US) + { + if (smart_warming_up) + { + ESP_LOGI(TAG, "Using smart warming up detection "); + + int16_t co2, last_co2; + last_co2 = dev->last_value; + // Sensor returns valid data after CPU reset and keep sensor powered + if (mhz19b_read_co2(dev, &co2) != ESP_OK) + return false; + if ((last_co2 != -1) && (last_co2 != co2)) + // CO2 value changed since last read, no longer warming-up + return false; + } + // Warming-up + return true; + } + + // Not warming-up + return false; +} + +bool mhz19b_is_ready(mhz19b_dev_t *dev) +{ + if (!dev) return false; + + // Minimum CO2 read interval (Built-in LED flashes) + if ((esp_timer_get_time() - dev->last_ts) > MHZ19B_READ_INTERVAL_MS) { + return true; + } + + return false; +} + +esp_err_t mhz19b_read_co2(mhz19b_dev_t *dev, int16_t *co2) +{ + CHECK_ARG(dev && co2); + + // Send command "Read CO2 concentration" + CHECK(mhz19b_send_command(dev, MHZ19B_CMD_READ_CO2, 0, 0, 0, 0, 0)); + + // 16-bit CO2 value in response Bytes 2 and 3 + *co2 = (dev->buf[2] << 8) | dev->buf[3]; + dev->last_ts = esp_timer_get_time(); + dev->last_value = *co2; + + return ESP_OK; +} + +esp_err_t mhz19b_get_version(mhz19b_dev_t *dev, char *version) +{ + CHECK_ARG(dev && version); + + // Clear version + memset(version, 0, 5); + + // Send command "Read firmware version" (NOT DOCUMENTED) + CHECK(mhz19b_send_command(dev, MHZ19B_CMD_GET_VERSION, 0, 0, 0, 0, 0)); + + // Copy 4 ASCII characters to version array like "0443" + for (uint8_t i = 0; i < 4; i++) { + // Version in response Bytes 2..5 + version[i] = dev->buf[i + 2]; + } + + return ESP_OK; +} + +esp_err_t mhz19b_set_range(mhz19b_dev_t *dev, mhz19b_range_t range) +{ + CHECK_ARG(dev); + + // Send "Set range" command + return mhz19b_send_command(dev, MHZ19B_CMD_SET_RANGE, + 0x00, 0x00, 0x00, (range >> 8), (range & 0xff)); +} + +esp_err_t mhz19b_get_range(mhz19b_dev_t *dev, uint16_t *range) +{ + CHECK_ARG(dev && range); + + // Send command "Read range" (NOT DOCUMENTED) + CHECK(mhz19b_send_command(dev, MHZ19B_CMD_GET_RANGE, 0, 0, 0, 0, 0)); + + // Range is in Bytes 4 and 5 + *range = (dev->buf[4] << 8) | dev->buf[5]; + + // Check range according to documented specification + if ((*range != MHZ19B_RANGE_2000) && (*range != MHZ19B_RANGE_5000)) + return ESP_ERR_INVALID_RESPONSE; + + return ESP_OK; +} + +esp_err_t mhz19b_set_auto_calibration(mhz19b_dev_t *dev, bool calibration_on) +{ + CHECK_ARG(dev); + + // Send command "Set Automatic Baseline Correction (ABC logic function)" + return mhz19b_send_command(dev, MHZ19B_CMD_SET_AUTO_CAL, (calibration_on ? 0xA0 : 0x00), 0, 0, 0, 0); +} + +esp_err_t mhz19b_get_auto_calibration(mhz19b_dev_t *dev, bool *calibration_on) +{ + CHECK_ARG(dev && calibration_on); + + // Send command "Get Automatic Baseline Correction (ABC logic function)" (NOT DOCUMENTED) + CHECK(mhz19b_send_command(dev, MHZ19B_CMD_GET_AUTO_CAL, 0, 0, 0, 0, 0)); + + // Response is located in Byte 7: 0 = off, 1 = on + *calibration_on = dev->buf[7] & 0x01; + + return ESP_OK; +} + +esp_err_t mhz19b_start_calibration(mhz19b_dev_t *dev) +{ + CHECK_ARG(dev); + + // Send command "Zero Point Calibration" + return mhz19b_send_command(dev, MHZ19B_CMD_CAL_ZERO_POINT, 0, 0, 0, 0, 0); +} + +esp_err_t mhz19b_send_command(mhz19b_dev_t *dev, uint8_t cmd, uint8_t b3, uint8_t b4, uint8_t b5, uint8_t b6, uint8_t b7) +{ + CHECK_ARG(dev && dev->buf); + + uint8_t txBuffer[MHZ19B_SERIAL_RX_BYTES] = { 0xFF, 0x01, cmd, b3, b4, b5, b6, b7, 0x00 }; + + // Check initialized +#if HELPER_TARGET_IS_ESP32 && ESP_IDF_VERSION >= ESP_IDF_VERSION_VAL(4, 0, 0) + if (!uart_is_driver_installed(dev->uart_port)) + return ESP_ERR_INVALID_STATE; +#endif + + // Add CRC Byte + txBuffer[8] = mhz19b_calc_crc(txBuffer); + + // Clear receive buffer + uart_flush(dev->uart_port); + + // Write serial data + uart_write_bytes(dev->uart_port, (char *) txBuffer, sizeof(txBuffer)); + + // Clear receive buffer + memset(dev->buf, 0, MHZ19B_SERIAL_BUF_LEN); + + // Read response from serial buffer + int len = uart_read_bytes(dev->uart_port, dev->buf, + MHZ19B_SERIAL_RX_BYTES, + MHZ19B_SERIAL_RX_TIMEOUT_MS / portTICK_RATE_MS); + if (len < 9) + return ESP_ERR_TIMEOUT; + + // Check received Byte[0] == 0xFF and Byte[1] == transmit command + if ((dev->buf[0] != 0xFF) || (dev->buf[1] != cmd)) + return ESP_ERR_INVALID_RESPONSE; + + // Check received Byte[8] CRC + if (dev->buf[8] != mhz19b_calc_crc(dev->buf)) + return ESP_ERR_INVALID_CRC; + + // Return result + return ESP_OK; +} + +// ---------------------------------------------------------------------------- +// Private functions +// ---------------------------------------------------------------------------- + +uint8_t mhz19b_calc_crc(uint8_t *data) +{ + uint8_t crc = 0; + + // Calculate CRC on 8 data Bytes + for (uint8_t i = 1; i < 8; i++) + crc += data[i]; + + crc = 0xFF - crc; + crc++; + + // Return calculated CRC + return crc; +} diff --git a/components/mhz19b/mhz19b.h b/components/mhz19b/mhz19b.h new file mode 100644 index 00000000..cdcca4da --- /dev/null +++ b/components/mhz19b/mhz19b.h @@ -0,0 +1,257 @@ +/** + * @file mhz19b.h + * @defgroup mhz19b mhz19b + * @{ + * + * ESP-IDF driver for MH-Z19B NDIR CO2 sensor connected to UART + * + * Inspired from https://github.com/Erriez/ErriezMHZ19B + * + * Copyright (C) 2020 Erriez + * Copyright (C) 2021 David Douard + * + * BSD Licensed as described in the file LICENSE + */ +#ifndef __MHZ19B_H__ +#define __MHZ19B_H__ + +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief MHZ19B sensor device data structure + */ +typedef struct +{ + uart_port_t uart_port; // UART port used to communicate + uint8_t *buf; // read buffer attached to this device + int16_t last_value; // last read value + int64_t last_ts; // timestamp of the last sensor co2 level reading +} mhz19b_dev_t; + +//! 3 minutes warming-up time after power-on before valid data returned +#define MHZ19B_WARMING_UP_TIME_MS (3UL * 60000UL) +#define MHZ19B_WARMING_UP_TIME_US (3UL * 60000UL * 1000UL) + +//! Minimum response time between CO2 reads (EXPERIMENTALLY DEFINED) +#define MHZ19B_READ_INTERVAL_MS (5UL * 1000UL) + +//! Fixed 9 Bytes response +#define MHZ19B_SERIAL_RX_BYTES 9 +#define MHZ19B_SERIAL_BUF_LEN 16 + +//! Response timeout between 15..120 ms at 9600 baud works reliable for all commands +#define MHZ19B_SERIAL_RX_TIMEOUT_MS 120 + +// Documented commands +#define MHZ19B_CMD_SET_AUTO_CAL 0x79 // set auto calibration on/off +#define MHZ19B_CMD_READ_CO2 0x86 // read CO2 concentration +#define MHZ19B_CMD_CAL_ZERO_POINT 0x87 // calibrate zero point at 400ppm +#define MHZ19B_CMD_CAL_SPAN_PIONT 0x88 // calibrate span point (NOT IMPLEMENTED) +#define MHZ19B_CMD_SET_RANGE 0x99 // set detection range + +// Not documented commands +#define MHZ19B_CMD_GET_AUTO_CAL 0x7D // get auto calibration status (NOT DOCUMENTED) +#define MHZ19B_CMD_GET_RANGE 0x9B // get range detection (NOT DOCUMENTED) +#define MHZ19B_CMD_GET_VERSION 0xA0 // get firmware version (NOT DOCUMENTED) + +/** + * @brief PPM range + */ +typedef enum { + MHZ19B_RANGE_2000 = 2000, // 2000 ppm + MHZ19B_RANGE_5000 = 5000, // 5000 ppm (Default) +} mhz19b_range_t; + + +/** + * @brief Initialize device descriptor + * + * @param dev Pointer to the sensor device data structure + * @param uart_port UART poert number + * @param tx_gpio GPIO pin number for TX + * @param rx_gpio GPIO pin number for RX + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_init(mhz19b_dev_t *dev, uart_port_t uart_port, gpio_num_t tx_gpio, gpio_num_t rx_gpio); + +/** + * @brief Free device descriptor + * + * @param dev Pointer to the sensor device data structure + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_free(mhz19b_dev_t *dev); + +/** + * @brief Detect sensor by checking range response + * + * @param dev Pointer to the sensor device data structure + * + * @return true if sensor is detected + */ +bool mhz19b_detect(mhz19b_dev_t *dev); + +/** + * @brief Check if sensor is warming up + * + * @param dev Pointer to the sensor device data structure + * @param smart_warming_up Smart check + * + * @return true if sensor is warming up + */ +bool mhz19b_is_warming_up(mhz19b_dev_t *dev, bool smart_warming_up); + +/** + * @brief Check minimum interval between CO2 reads + * + * Not described in the datasheet, but it is the same frequency as the built-in LED blink. + * + * @param dev Pointer to the sensor device data structure + * + * @return true if ready to call ::mhz19b_read_co2() + */ +bool mhz19b_is_ready(mhz19b_dev_t *dev); + +/** + * @brief Read CO2 from sensor + * + * @param dev Pointer to the sensor device data structure + * @param co2 co2 level (output) + * <0 + * MH-Z19B response error codes. + * 0..399 + * ppmIncorrect values. Minimum value starts at 400ppm outdoor fresh air. + * 400..1000 ppm + * Concentrations typical of occupied indoor spaces with good air exchange. + * 1000..2000 ppm + * Complaints of drowsiness and poor air quality. Ventilation is required. + * 2000..5000 ppm + * Headaches, sleepiness and stagnant, stale, stuffy air. Poor concentration, loss of + * attention, increased heart rate and slight nausea may also be present.\n + * Higher values are extremely dangerous and cannot be measured. + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_read_co2(mhz19b_dev_t *dev, int16_t *co2); + +/** + * @brief Get firmware version (NOT DOCUMENTED) + * + * @details + * This is an undocumented command, but most sensors returns ASCII "0430 or "0443". + * + * @param dev Pointer to the sensor device data structure + * @param version + * Returned character pointer to version (must be at least 5 Bytes)\n + * Only valid when return is set to ESP_OK. + * @param versionLen + * Number of characters including NULL of version buffer. + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_get_version(mhz19b_dev_t *dev, char *version); + +/** + * @brief Set CO2 range + * + * @param dev Pointer to the sensor device data structure + * @param range Range of the sensor (2000 or 5000, in ppm) + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_set_range(mhz19b_dev_t *dev, mhz19b_range_t range); + +/** + * @brief Get CO2 range in PPM (NOT DOCUMENTED) + * + * @details + * This function verifies valid read ranges of 2000 or 5000 ppm.\n + * Note: Other ranges may be returned, but are undocumented and marked as invalid. + * + * @param dev Pointer to the sensor device data structure + * @param range Current value of the range of the sensor (output) + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_get_range(mhz19b_dev_t *dev, uint16_t *range); + +/** + * @brief Enable or disable automatic calibration + * + * @param dev Pointer to the sensor device data structure + * @param calibration_on + * true: Automatic calibration on.\n + * false: Automatic calibration off. + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_set_auto_calibration(mhz19b_dev_t *dev, bool calibration_on); + +/** + * @brief Get status automatic calibration (NOT DOCUMENTED) + * + * @param dev Pointer to the sensor device data structure + * @param calibration_on (output) + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_get_auto_calibration( + mhz19b_dev_t *dev, bool *calibration_on); // (NOT DOCUMENTED) + +/** + * @brief Start Zero Point Calibration manually at 400ppm + * + * @details + * The sensor must be powered-up for at least 20 minutes in fresh air at 400ppm room + * temperature. Then call this function once to execute self calibration.\n + * Recommended to use this function when auto calibrate turned off. + * + * @param dev Pointer to the sensor device data structure + * + * @return ESP_OK on success + */ +esp_err_t mhz19b_start_calibration(mhz19b_dev_t *dev); + +/** + * @brief Send serial command to sensor and read response + * + * @details + * Send command to sensor and read response, protected with a receive timeout.\n + * Result is available in public rxBuffer[9]. + * + * @param dev Pointer to the sensor device data structure + * @param cmd Command Byte + * @param b3 Byte 3 (default 0) + * @param b4 Byte 4 (default 0) + * @param b5 Byte 5 (default 0) + * @param b6 Byte 6 (default 0) + * @param b7 Byte 7 (default 0) + */ +esp_err_t mhz19b_send_command(mhz19b_dev_t *dev, uint8_t cmd, + uint8_t b3, uint8_t b4, uint8_t b5, + uint8_t b6, uint8_t b7); + +/** + * @brief Calculate CRC on 8 data Bytes buffer + * + * @param data Buffer pointer to calculate CRC. + * @return Calculated 8-bit CRC. + */ +uint8_t mhz19b_calc_crc(uint8_t *data); + +#ifdef __cplusplus +} +#endif /* End of CPP guard */ + +/**@}*/ + +#endif /* __MHZ19B_H__ */ diff --git a/docs/source/groups/mhz19b.rst b/docs/source/groups/mhz19b.rst new file mode 100644 index 00000000..497938a1 --- /dev/null +++ b/docs/source/groups/mhz19b.rst @@ -0,0 +1,7 @@ +.. _mhz19b: + +mhz19b - Driver for MH-Z19B NDIR CO2 sensor connected to UART +============================================================= + +.. doxygengroup:: mhz19b + :members: diff --git a/docs/source/index.rst b/docs/source/index.rst index fb430fd7..2ff03e31 100644 --- a/docs/source/index.rst +++ b/docs/source/index.rst @@ -137,6 +137,7 @@ Air quality/Gas sensors groups/sgp40 groups/ccs811 + groups/mhz19b ADC/DAC ======= diff --git a/examples/mhz19b/CMakeLists.txt b/examples/mhz19b/CMakeLists.txt new file mode 100644 index 00000000..82b4ab12 --- /dev/null +++ b/examples/mhz19b/CMakeLists.txt @@ -0,0 +1,8 @@ +# The following four lines of boilerplate have to be in your project's CMakeLists +# in this exact order for cmake to work correctly +cmake_minimum_required(VERSION 3.5) + +set(EXTRA_COMPONENT_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../../components) + +include($ENV{IDF_PATH}/tools/cmake/project.cmake) +project(example-mhz19b) diff --git a/examples/mhz19b/Makefile b/examples/mhz19b/Makefile new file mode 100644 index 00000000..b2b5d13b --- /dev/null +++ b/examples/mhz19b/Makefile @@ -0,0 +1,6 @@ +#V := 1 +PROJECT_NAME := example-mhz19b + +EXTRA_COMPONENT_DIRS := $(CURDIR)/../../components + +include $(IDF_PATH)/make/project.mk diff --git a/examples/mhz19b/main/CMakeLists.txt b/examples/mhz19b/main/CMakeLists.txt new file mode 100644 index 00000000..8a9d914e --- /dev/null +++ b/examples/mhz19b/main/CMakeLists.txt @@ -0,0 +1,2 @@ +idf_component_register(SRCS "main.c" + INCLUDE_DIRS ".") diff --git a/examples/mhz19b/main/component.mk b/examples/mhz19b/main/component.mk new file mode 100644 index 00000000..004b18e6 --- /dev/null +++ b/examples/mhz19b/main/component.mk @@ -0,0 +1 @@ +COMPONENT_ADD_INCLUDEDIRS = . diff --git a/examples/mhz19b/main/main.c b/examples/mhz19b/main/main.c new file mode 100644 index 00000000..bf3849ec --- /dev/null +++ b/examples/mhz19b/main/main.c @@ -0,0 +1,52 @@ +#include +#include +#include +#include +#include + +#define TAG "MHZ19BDEMO" + +#define MHZ19B_TX 12 +#define MHZ19B_RX 13 + +void app_main(void) +{ + int16_t co2; + mhz19b_dev_t dev; + char version[6]; + uint16_t range; + bool autocal; + + ESP_ERROR_CHECK(mhz19b_init(&dev, UART_NUM_1, MHZ19B_TX, MHZ19B_RX)); + + while (!mhz19b_detect(&dev)) + { + ESP_LOGI(TAG, "MHZ-19B not detected, waiting..."); + vTaskDelay(1000 / portTICK_RATE_MS); + } + + mhz19b_get_version(&dev, version); + ESP_LOGI(TAG, "MHZ-19B firmware version: %s", version); + ESP_LOGI(TAG, "MHZ-19B set range and autocal"); + + mhz19b_set_range(&dev, MHZ19B_RANGE_5000); + mhz19b_set_auto_calibration(&dev, false); + + mhz19b_get_range(&dev, &range); + ESP_LOGI(TAG, " range: %d", range); + + mhz19b_get_auto_calibration(&dev, &autocal); + ESP_LOGI(TAG, " autocal: %s", autocal ? "ON" : "OFF"); + + while (mhz19b_is_warming_up(&dev, true)) // use smart warming up detection + { + ESP_LOGI(TAG, "MHZ-19B is warming up"); + vTaskDelay(1000 / portTICK_RATE_MS); + } + + while (1) { + mhz19b_read_co2(&dev, &co2); + ESP_LOGI(TAG, "CO2: %d", co2); + vTaskDelay(5000 / portTICK_RATE_MS); + } +}