diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep index 3d2e780b56..e313b9d206 100644 --- a/drivers/Makefile.dep +++ b/drivers/Makefile.dep @@ -464,6 +464,18 @@ ifneq (,$(filter mag3110,$(USEMODULE))) FEATURES_REQUIRED += periph_i2c endif +ifneq (,$(filter mhz19_pwm,$(USEMODULE))) + FEATURES_REQUIRED += periph_gpio + USEMODULE += xtimer + USEMODULE += mhz19 +endif + +ifneq (,$(filter mhz19_uart,$(USEMODULE))) + FEATURES_REQUIRED += periph_uart + USEMODULE += xtimer + USEMODULE += mhz19 +endif + ifneq (,$(filter mma7660,$(USEMODULE))) FEATURES_REQUIRED += periph_i2c endif diff --git a/drivers/Makefile.include b/drivers/Makefile.include index e9d78958ae..9d4d3d9746 100644 --- a/drivers/Makefile.include +++ b/drivers/Makefile.include @@ -240,6 +240,10 @@ ifneq (,$(filter mag3110,$(USEMODULE))) USEMODULE_INCLUDES += $(RIOTBASE)/drivers/mag3110/include endif +ifneq (,$(filter mhz19,$(USEMODULE))) + USEMODULE_INCLUDES += $(RIOTBASE)/drivers/mhz19/include +endif + ifneq (,$(filter mma7660,$(USEMODULE))) USEMODULE_INCLUDES += $(RIOTBASE)/drivers/mma7660/include endif diff --git a/drivers/include/mhz19.h b/drivers/include/mhz19.h new file mode 100644 index 0000000000..28e1b0dc18 --- /dev/null +++ b/drivers/include/mhz19.h @@ -0,0 +1,157 @@ +/* + * Copyright (C) 2018 Koen Zandberg + * Copyright (C) 2018 Beduino Master Projekt - University of Bremen + * Copyright (C) 2020 Bas Stottelaar + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @defgroup drivers_mhz19 MH-Z19 CO2 sensor + * @ingroup drivers_sensors + * + * @brief MH-Z19 CO2 sensor driver + * + * ## Description + * + * The MH-Z19 is a CO2 sensor. Measurements are provided in parts per million + * (ppm) over UART and PWM. The ppm value ranges from 0 (theoretically) to + * 2000 or 5000, depending on the sensor settings. + * + * In UART mode, additional commands are available to configure the sensor. + * + * Note that the sensor requires considerable time before accurate measurements + * are provided. + * + * @{ + * + * @file + * @brief Interface definition for the MH-Z19 CO2 sensor driver. + * + * @author Koen Zandberg + * @author Christian Manal + * @author Bas Stottelaar + */ + +#ifndef MHZ19_H +#define MHZ19_H + +#include + +#include "saul.h" + +#ifdef MODULE_MHZ19_UART +#include "periph/uart.h" +#include "mhz19_internals.h" +#include "mutex.h" +#endif /* MODULE_MHZ19_UART */ + +#ifdef MODULE_MHZ19_PWM +#include "periph/gpio.h" +#endif /* MODULE_MHZ19_PWM */ + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Status and error return codes + */ +enum { + MHZ19_OK = 0, /**< everything was fine */ + MHZ19_ERR_INIT = -1, /**< error initializing the device */ + MHZ19_ERR_TIMEOUT = -2, /**< timeout on retrieving sensor data */ + MHZ19_ERR_CHECKSUM = -3, /**< checksum failure on received data */ +}; + +#ifdef MODULE_MHZ19_UART +/** + * @brief Device initialization parameters + */ +typedef struct { + uart_t uart; /**< UART device that sensor is connected to */ + bool auto_calibration; /** enable or disable auto calibration */ +} mhz19_params_t; + +/** + * @brief Device descriptor for a MH-Z19 device + */ +typedef struct { + const mhz19_params_t *params; /**< device parameters */ + mutex_t mutex; /**< protect against simulaneous access */ + mutex_t sync; /**< transfer complete or timeout sync */ + uint8_t idx; /**< rx buffer index */ + uint8_t rxmem[MHZ19_BUF_SIZE]; /**< rx buffer */ +} mhz19_t; +#endif /* MODULE_MHZ19_UART */ + +#ifdef MODULE_MHZ19_PWM +/** + * @brief Device initialization parameters + */ +typedef struct { + gpio_t pin; /**< Pin the sensor is connected to */ +} mhz19_params_t; + +/** + * @brief Device descriptor for a mhz19 driver + */ +typedef struct { + gpio_t pin; /**< Pin the sensor is connected to */ +} mhz19_t; +#endif /* MODULE_MHZ19_PWM */ + +/** + * @brief Export SAUL endpoint + */ +extern const saul_driver_t mhz19_ppm_saul_driver; + +/** + * @brief Initialize a MH-Z19 device + * + * @param[out] dev device descriptor + * @param[in] params MH-Z19 initialization struct + * + * @return MHZ19_OK + * @return MHZ19_ERR_INIT + */ +int mhz19_init(mhz19_t *dev, const mhz19_params_t *params); + +/** + * @brief Get measured CO2 ppm value + * + * @param[in] dev device descriptor + * @param[out] ppm int16_t buffer where CO2 measurement will be + * written to, in ppm + * + * @return MHZ19_OK + * @return MHZ19_ERR_TIMEOUT + * @return MHZ19_ERR_CHECKSUM + */ +int mhz19_get_ppm(mhz19_t *dev, int16_t *ppm); + +#ifdef MODULE_MHZ19_UART +/** + * @brief Enable or disable auto base calibration + * + * @param[in] dev device descriptor + * @param[in] enable true to enable, false to disable + */ +void mhz19_set_auto_calibration(mhz19_t *dev, bool enable); + +/** + * @brief Calibrate zero point + * + * @param[in] dev device descriptor + */ +void mhz19_calibrate_zero_point(mhz19_t *dev); +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* MHZ19_H */ +/** @} */ diff --git a/drivers/mhz19/Makefile b/drivers/mhz19/Makefile new file mode 100644 index 0000000000..48422e909a --- /dev/null +++ b/drivers/mhz19/Makefile @@ -0,0 +1 @@ +include $(RIOTBASE)/Makefile.base diff --git a/drivers/mhz19/include/mhz19_internals.h b/drivers/mhz19/include/mhz19_internals.h new file mode 100644 index 0000000000..2913582661 --- /dev/null +++ b/drivers/mhz19/include/mhz19_internals.h @@ -0,0 +1,100 @@ +/* + * Copyright (C) 2018 Koen Zandberg + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup drivers_mhz19 + * @{ + * @file + * @brief Internal addresses, registers, constants for the MH-Z19 CO2 + * sensor + * + * @author Koen Zandberg + */ + +#ifndef MHZ19_INTERNALS_H +#define MHZ19_INTERNALS_H + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name MH-Z19 Baud rate + * + * Fixed at 9600 by design. + */ +#define MHZ19_UART_BAUDRATE 9600 + +/** + * @name MH-Z19 Buffer size + * + * A transmission from the MH-Z19 is 9 bytes long: + * 1 Start byte + * 1 Sensor number + * 2 bytes data + * 4 bytes padding + * 1 byte checksum + * + * The start byte is not stored because it is not used in the checksum + * calculation. + */ +#define MHZ19_BUF_SIZE 8 + +/** + * @name MH-Z19 Timeout in milliseconds + * + * 20 ms gives a decent margin on top of the UART transmission time. The + * datasheet does not specify any timings beside the UART baud rate. + * + * A single byte takes 10 bits effectively: a start bit, 8 bits data + * and stop bit. 9 bytes are transmitted, thus 10 bits * 9 / 9600bps = 9.3 ms. + */ +#define MHZ19_TIMEOUT_READ 20 + +/*** + * @name MH-Z19 Command timeout in milliseconds + * + * While undocumented, it seems that some commands take some time. Without + * an additional delay, the first sensor read will fail with a timeout value, + * or return an arbitrary value. + */ +#define MHZ19_TIMEOUT_CMD (MHZ19_TIMEOUT_READ * 5) + +/** + * @name MH-Z19 transmission constants + * @{ + */ +#define MHZ19_READ_START 0xff /**< Start bytes */ +#define MHZ19_READ_SENSOR_NUM 0x01 /**< Sensor number */ +/** @} */ + +/** + * @name MH-Z19 commands + * @{ + */ +#define MHZ19_CMD_AUTO_CALIBRATION 0x79 /**< Auto calibration command */ +#define MHZ19_CMD_GAS_CONCENTRATION 0x86 /**< Gas concentration command */ +#define MHZ19_CMD_CALIBRATE_ZERO 0x87 /**< Zero calibration command */ +#define MHZ19_CMD_CALIBRATE_SPAN 0x88 /**< Span calibration command */ +/** @} */ + +/** + * @name MH-Z19 transmission data positions + * @{ + */ +#define MHZ19_RX_POS_PPM_HIGH 1 /**< Measurement high byte */ +#define MHZ19_RX_POS_PPM_LOW 2 /**< Measurement low byte */ +#define MHZ19_RX_POS_CHECKSUM 7 /**< Checksum position */ +/** @} */ + +#ifdef __cplusplus +} +#endif + +#endif /* MHZ19_INTERNALS_H */ +/** @} */ diff --git a/drivers/mhz19/include/mhz19_params.h b/drivers/mhz19/include/mhz19_params.h new file mode 100644 index 0000000000..cd26ca2550 --- /dev/null +++ b/drivers/mhz19/include/mhz19_params.h @@ -0,0 +1,84 @@ +/* + * Copyright (C) 2018 Koen Zandberg + * Copyright (C) 2018 Beduino Master Projekt - University of Bremen + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup drivers_mhz19 + * + * @{ + * @file + * @brief Default configuration for MH-Z19 + * + * @author Koen Zandberg + * @author Christian Manal + */ + +#ifndef MHZ19_PARAMS_H +#define MHZ19_PARAMS_H + +#include "board.h" +#include "mhz19.h" +#include "saul_reg.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @name Set default configuration parameters for the MH-Z19 + * @{ + */ +#ifdef MODULE_MHZ19_UART +#ifndef MHZ19_PARAM_UART_DEV +#define MHZ19_PARAM_UART_DEV UART_DEV(1) +#endif + +#ifndef MHZ19_PARAMS +#define MHZ19_PARAMS { .uart = MHZ19_PARAM_UART_DEV } +#endif +#endif /* MODULE_MHZ19_UART */ + +#ifdef MODULE_MHZ19_PWM +#ifndef MHZ19_PARAM_PIN +#define MHZ19_PARAM_PIN (GPIO_PIN(0, 0)) +#endif + +#ifndef MHZ19_PARAMS +#define MHZ19_PARAMS { .pin = MHZ19_PARAM_PIN } +#endif +#endif /* MODULE_MHZ19_PWM */ + +#ifndef MHZ19_SAUL_INFO +#define MHZ19_SAUL_INFO { .name = "mh-z19" } +#endif +/** + * @brief Configure MHZ19 + */ +static const mhz19_params_t mhz19_params[] = +{ + MHZ19_PARAMS +}; + +/** + * @brief Configuration details of SAUL registry entries + * + * This two dimensional array contains static details of the sensors + * for each device. Please be awar that the indexes are used in + * auto_init_mhz280, so make sure the indexes match. + */ +static const saul_reg_info_t mhz19_saul_info[] = +{ + MHZ19_SAUL_INFO +}; + +#ifdef __cplusplus +} +#endif + +#endif /* MHZ19_PARAMS_H */ +/** @} */ diff --git a/drivers/mhz19/mhz19_pwm.c b/drivers/mhz19/mhz19_pwm.c new file mode 100644 index 0000000000..af15aba527 --- /dev/null +++ b/drivers/mhz19/mhz19_pwm.c @@ -0,0 +1,102 @@ +/* + * Copyright (C) 2018 Koen Zandberg + * Copyright (C) 2018 Beduino Master Projekt - University of Bremen + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup drivers_mhz19 + * @{ + * + * @file + * @brief Device driver implementation for MH-Z19 CO2 sensor. + * + * @author Koen Zandberg + * @author Christian Manal + * + * @} + */ + +#include "mhz19.h" +#include "mhz19_params.h" +#include "xtimer.h" +#include "mutex.h" + +#define ENABLE_DEBUG (0) +#include "debug.h" + +#ifdef MODULE_MHZ19_PWM +int mhz19_init(mhz19_t *dev, const mhz19_params_t *params) +{ + int16_t res; + + dev->pin = params->pin; + + if (gpio_init(dev->pin, GPIO_IN_PD) != 0) { + return MHZ19_ERR_INIT; + } + + /* Take one measurement to make sure there's an mhz19 on the pin */ + if (mhz19_get_ppm(dev, &res) == MHZ19_ERR_TIMEOUT) { + return MHZ19_ERR_TIMEOUT; + } + + return MHZ19_OK; +} + +int mhz19_get_ppm(mhz19_t *dev, int16_t *ppm) +{ + uint32_t start, middle, end, th, tl; + /* + * Per the docs, one sample should take 1004ms +-5%. Worst case is + * that we come in right after the rising edge of the current cycle, + * so we want to wait two cycles plus some wiggle room at most for + * a measurement. + */ + int16_t timeout = 2200; + + DEBUG("%s: Waiting for high level to end\n", __func__); + while (gpio_read(dev->pin) && timeout) { + timeout--; + xtimer_usleep(US_PER_MS); + } + + DEBUG("%s: Waiting for initial rising edge\n", __func__); + while (!gpio_read(dev->pin) && timeout) { + timeout--; + xtimer_usleep(US_PER_MS); + } + + start = xtimer_now_usec() / US_PER_MS; + DEBUG("%s: Waiting for falling edge\n", __func__); + while (gpio_read(dev->pin) && timeout) { + timeout--; + xtimer_usleep(US_PER_MS); + } + middle = xtimer_now_usec() / US_PER_MS; + DEBUG("%s: Waiting for rising edge\n", __func__); + while (!gpio_read(dev->pin) && timeout) { + timeout--; + xtimer_usleep(US_PER_MS); + } + + /* If we waited too long for flanks, something went wrong */ + if (!timeout) { + DEBUG("%s: Measurement timed out\n", __func__); + return MHZ19_ERR_TIMEOUT; + } + end = xtimer_now_usec() / US_PER_MS; + + th = (middle - start); + tl = (end - middle); + + *ppm = (int16_t)(2000 * (th - 2) / (th + tl - 4)); + + return MHZ19_OK; +} +#else +typedef int dont_be_pedantic; +#endif /* MODULE_MHZ19_PWM */ diff --git a/drivers/mhz19/mhz19_saul.c b/drivers/mhz19/mhz19_saul.c new file mode 100644 index 0000000000..cf0a11cfde --- /dev/null +++ b/drivers/mhz19/mhz19_saul.c @@ -0,0 +1,42 @@ +/* + * Copyright (C) 2018 Koen Zandberg + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup drivers_mhz19 + * @{ + * + * @file + * @brief SAUL adaption for MH-Z19 CO2 sensor device + * + * @author Koen Zandberg + * + * @} + */ + +#include "saul.h" +#include "mhz19.h" + +static int read_ppm(const void *dev, phydat_t *res) +{ + int16_t ppm; + + /* Drops the const keyword, otherwise the mutex can't be locked */ + if (mhz19_get_ppm((mhz19_t *)dev, &ppm) < 0) { + return -ECANCELED; + } + res->val[0] = ppm; + res->unit = UNIT_PPM; + res->scale = 0; + return 1; +} + +const saul_driver_t mhz19_ppm_saul_driver = { + .read = read_ppm, + .write = saul_notsup, + .type = SAUL_SENSE_CO2 +}; diff --git a/drivers/mhz19/mhz19_uart.c b/drivers/mhz19/mhz19_uart.c new file mode 100644 index 0000000000..f778222a75 --- /dev/null +++ b/drivers/mhz19/mhz19_uart.c @@ -0,0 +1,238 @@ +/* + * Copyright (C) 2018 Koen Zandberg + * Copyright (C) 2018 Beduino Master Projekt - University of Bremen + * Copyright (C) 2020 Bas Stottelaar + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup drivers_mhz19 + * @{ + * + * @file + * @brief Device driver implementation for MH-Z19 CO2 sensor. + * + * @author Koen Zandberg + * @author Christian Manal + * @author Bas Stottelaar + * + * @} + */ + +#include "mhz19.h" +#include "mhz19_params.h" +#include "xtimer.h" +#include "mutex.h" + +#define ENABLE_DEBUG (0) +#include "debug.h" + +#ifdef MODULE_MHZ19_UART +#include "mhz19_internals.h" + +/* Precalculated command sequences */ +static const uint8_t value_read[] = { + MHZ19_READ_START, + MHZ19_READ_SENSOR_NUM, + MHZ19_CMD_GAS_CONCENTRATION, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x79 /* checksum */ +}; + +static const uint8_t auto_calibration_on[] = { + MHZ19_READ_START, + MHZ19_READ_SENSOR_NUM, + MHZ19_CMD_AUTO_CALIBRATION, + 0xA0, /* on */ + 0x00, + 0x00, + 0x00, + 0x00, + 0xE6 /* checksum */ +}; + +static const uint8_t auto_calibration_off[] = { + MHZ19_READ_START, + MHZ19_READ_SENSOR_NUM, + MHZ19_CMD_AUTO_CALIBRATION, + 0x00, /* off */ + 0x00, + 0x00, + 0x00, + 0x00, + 0x86 /* checksum */ +}; + +static const uint8_t calibrate_zero_point[] = { + MHZ19_READ_START, + MHZ19_READ_SENSOR_NUM, + MHZ19_CMD_CALIBRATE_ZERO, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x78 /* checksum */ +}; + +static void _mhz19_rx_cb(void *arg, uint8_t byte) +{ + mhz19_t *dev = arg; + + /* Skip start byte and skip out of array bounds writes */ + if ((dev->idx == 0 && byte == 0xff) || dev->idx >= MHZ19_BUF_SIZE) { + return; + } + /* Store byte and increment idx */ + dev->rxmem[dev->idx++] = byte; + if (dev->idx == MHZ19_BUF_SIZE) { + mutex_unlock(&dev->sync); + } +} + +int mhz19_init(mhz19_t *dev, const mhz19_params_t *params) +{ + dev->params = params; + + DEBUG("mhz19: initializing device %p on UART %i\n", + (void *)dev, dev->params->uart); + + mutex_init(&dev->mutex); + mutex_init(&dev->sync); + + dev->idx = 0; + + /* Initialize UART interface */ + if (uart_init(params->uart, MHZ19_UART_BAUDRATE, _mhz19_rx_cb, dev)) { + DEBUG("mhz19: UART initialization failed\n"); + return MHZ19_ERR_INIT; + } + + /* set auto calibration to a know value */ + mhz19_set_auto_calibration(dev, params->auto_calibration); + + DEBUG("mhz19: initialization complete\n"); + return MHZ19_OK; +} + +/* + * Do a raw send command to the sensor, without waiting for data. + * + * @param[in] dev The mhz19 device context + * @param[in] out the 9 bytes to transmit to the device + */ +static void mhz19_cmd(mhz19_t *dev, const uint8_t *in) +{ + /* First lock, guarantees no concurrent access to the UART device */ + mutex_lock(&dev->mutex); + + /* send the command */ + uart_write(dev->params->uart, in, MHZ19_BUF_SIZE + 1); + + /* Add some delay after executing command */ + xtimer_usleep(MHZ19_TIMEOUT_CMD * US_PER_MS); + + /* Unlock concurrency guard mutex */ + mutex_unlock(&dev->mutex); +} + +/* + * Do a raw send/receive exchange to the sensor. As exchanges between the + * MH-Z19 and the host always consists of 9 bytes in each direction, the size + * of the input and output arrays is fixed at 9 bytes here. The returned bytes + * from the MH-Z19 appear in mhz19_t::rxmem + * + * @param[in] dev The mhz19 device context + * @param[in] out the 9 bytes to transmit to the device + */ +static void mhz19_xmit(mhz19_t *dev, const uint8_t *in) +{ + /* Reset the buffer index to zero */ + dev->idx = 0; + + /* Lock the synchronization mutex */ + mutex_lock(&dev->sync); + + /* Send read command to the sensor */ + uart_write(dev->params->uart, in, MHZ19_BUF_SIZE + 1); + + /* By locking the same mutex another time, this thread blocks until + * the UART ISR received all bytes and unlocks the mutex. If that does not + * happen, then xtimer_mutex_lock_timeout unlocks the mutex after as well + * after the timeout expired. + */ + xtimer_mutex_lock_timeout(&dev->sync, MHZ19_TIMEOUT_CMD * US_PER_MS); + + /* Unlock synchronization for next transmission */ + mutex_unlock(&dev->sync); +} + +int mhz19_get_ppm(mhz19_t *dev, int16_t *ppm) +{ + int res = MHZ19_OK; + + /* First lock, guarantees no concurrent access to the UART device */ + mutex_lock(&dev->mutex); + + DEBUG("mhz19: Starting measurement\n"); + mhz19_xmit(dev, value_read); + + DEBUG("mhz19: Checking buffer: %d\n", dev->idx); + /* MHZ19_BUF_SIZE indicates completely filled buffer */ + if (dev->idx == MHZ19_BUF_SIZE) { + uint8_t checksum = 0; + /* MHZ19_BUF_SIZE - 1 to exclude the received checksum */ + for (unsigned i = 0; i < MHZ19_BUF_SIZE - 1; i++) { + checksum -= dev->rxmem[i]; + } + if (checksum == dev->rxmem[MHZ19_RX_POS_CHECKSUM]) { + *ppm = dev->rxmem[MHZ19_RX_POS_PPM_HIGH] << 8; + *ppm += dev->rxmem[MHZ19_RX_POS_PPM_LOW]; + res = MHZ19_OK; + } + else { + /* Checksum mismatch */ + DEBUG("mhz19: Checksum failed, calculated 0x%x != 0x%x\n", checksum, + dev->rxmem[MHZ19_RX_POS_CHECKSUM]); + res = MHZ19_ERR_CHECKSUM; + } + } + else { + DEBUG("mhz19: Timeout trying to retrieve measurement\n"); + res = MHZ19_ERR_TIMEOUT; + } + + /* Unlock concurrency guard mutex */ + mutex_unlock(&dev->mutex); + + return res; +} + +void mhz19_set_auto_calibration(mhz19_t *dev, bool enable) +{ + DEBUG("mhz19: setting autocalibration to %d\n", (int)enable); + + if (enable) { + mhz19_cmd(dev, auto_calibration_on); + } + else { + mhz19_cmd(dev, auto_calibration_off); + } +} + +void mhz19_calibrate_zero_point(mhz19_t *dev) +{ + DEBUG("mhz19: calibrating zero point\n"); + + mhz19_cmd(dev, calibrate_zero_point); +} +#else +typedef int dont_be_pedantic; +#endif /* MODULE_MHZ19_UART */ diff --git a/drivers/saul/init_devs/auto_init_mhz19.c b/drivers/saul/init_devs/auto_init_mhz19.c new file mode 100644 index 0000000000..0d012e5289 --- /dev/null +++ b/drivers/saul/init_devs/auto_init_mhz19.c @@ -0,0 +1,71 @@ +/* + * Copyright (C) 2018 Koen Zandberg + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @ingroup sys_auto_init_saul + * @{ + * + * @file + * @brief Auto initialization of MH-Z19 C02 sensor device. + * + * @author Koen Zandberg + * + * @} + */ + +#include "assert.h" +#include "log.h" +#include "saul_reg.h" +#include "mhz19.h" +#include "mhz19_params.h" + +/** + * @brief Define the number of configured sensors + */ +#define MHZ19_NUM ARRAY_SIZE(mhz19_params) + +/** + * @brief Allocation of memory for device descriptors + */ +static mhz19_t mhz19_devs[MHZ19_NUM]; + +/** + * @brief Memory for the SAUL registry entries + */ +static saul_reg_t saul_entries[MHZ19_NUM]; + +/** + * @brief Define the number of saul info + */ +#define MHZ19_INFO_NUM ARRAY_SIZE(mhz19_saul_info) + +/** + * @brief Reference the driver structs. + */ +extern const saul_driver_t mhz19_ppm_saul_driver; + +void auto_init_mhz19(void) +{ + assert(MHZ19_NUM == MHZ19_INFO_NUM); + + for (unsigned i = 0; i < MHZ19_NUM; i++) { + LOG_DEBUG("[auto_init_saul] initializing mhz19 #%u\n", i); + + if (mhz19_init(&mhz19_devs[i], &mhz19_params[i]) < 0) { + LOG_ERROR("[auto_init_saul] error initializing mhz19 #%u\n", i); + continue; + } + + saul_entries[i].dev = &(mhz19_devs[i]); + saul_entries[i].name = mhz19_saul_info[i].name; + saul_entries[i].driver = &mhz19_ppm_saul_driver; + + /* register to saul */ + saul_reg_add(&(saul_entries[i])); + } +} diff --git a/drivers/saul/init_devs/init.c b/drivers/saul/init_devs/init.c index f328e34fcf..2b52ff8640 100644 --- a/drivers/saul/init_devs/init.c +++ b/drivers/saul/init_devs/init.c @@ -171,6 +171,10 @@ void saul_init_devs(void) extern void auto_init_mag3110(void); auto_init_mag3110(); } + if (IS_USED(MODULE_MHZ19)) { + extern void auto_init_mhz19(void); + auto_init_mhz19(); + } if (IS_USED(MODULE_MMA7660)) { extern void auto_init_mma7660(void); auto_init_mma7660(); diff --git a/makefiles/pseudomodules.inc.mk b/makefiles/pseudomodules.inc.mk index d9793255a1..112a4f2c86 100644 --- a/makefiles/pseudomodules.inc.mk +++ b/makefiles/pseudomodules.inc.mk @@ -164,6 +164,10 @@ PSEUDOMODULES += hmc5883l_int # interrupt variant of the ITG320X driver as pseudo module PSEUDOMODULES += itg320x_int +# include variants of MH-Z19 drivers as pseudo modules +PSEUDOMODULES += mhz19_uart +PSEUDOMODULES += mhz19_pwm + # include variants of MPU9X50 drivers as pseudo modules PSEUDOMODULES += mpu9150 PSEUDOMODULES += mpu9250